RobWorkProject  23.9.11-
Classes | Public Types | Public Member Functions | Protected Attributes | List of all members
RigidBody Class Reference

A body is an abstraction over some physical object in the scene. The body class is an abstract class that allows interaction by adding gravity, forces and impulses. The integration scheme used to update the velocity and position of the body is defined by the class that inherit the body interface. More...

#include <RigidBody.hpp>

Inherits Body.

Classes

struct  RigidBodyState
 The state of a rigid body. More...
 

Public Types

typedef rw::core::Ptr< RigidBodyPtr
 Smart pointer type for a RigidBody.
 
- Public Types inherited from Body
enum  BodyEventType { MassChangedEvent }
 Types of events a body can emit. More...
 
typedef rw::core::Ptr< BodyPtr
 Smart pointer type for a Body.
 
typedef boost::function< void(BodyEventType)> BodyChangedListener
 Defines a state changed listener. More...
 
typedef rw::core::Event< BodyChangedListener, BodyEventTypeBodyChangedEvent
 Type for body events.
 
- Public Types inherited from Stateless
typedef rw::core::Ptr< StatelessPtr
 Smart pointer type for Stateless.
 

Public Member Functions

 RigidBody (const BodyInfo &info, rw::models::Object::Ptr obj)
 Construct a new dynamic body. More...
 
virtual ~RigidBody ()
 Destructor.
 
rw::math::Vector3D getPointVelW (const rw::math::Vector3D<> &p, const rw::kinematics::State &state) const
 calculates the relative velocity of a point p on the body described in world frames. More...
 
rw::math::VelocityScrew6D getVelocity (const rw::kinematics::State &state) const
 gets the velocity of this body relative to the parent frame More...
 
void reset (rw::kinematics::State &state)
 reset the state variables of this body More...
 
double calcEnergy (const rw::kinematics::State &state, const rw::math::Vector3D<> &gravity=rw::math::Vector3D<>::zero(), const rw::math::Vector3D<> &potZero=rw::math::Vector3D<>::zero()) const
 Calculates the total energy of the body. More...
 
void setForce (const rw::math::Vector3D<> &f, rw::kinematics::State &state)
 Sets the force described in parent frame acting on the center mass of this body. More...
 
void addForce (const rw::math::Vector3D<> &force, rw::kinematics::State &state)
 Adds a force described in parent frame to the center of mass of this body. More...
 
rw::math::Vector3D getForce (const rw::kinematics::State &state) const
 Gets the force described in parent frame acting on the center mass of this body. More...
 
void setTorque (const rw::math::Vector3D<> &t, rw::kinematics::State &state)
 set the torque of this body with torque t, where t is described in body frame More...
 
void addTorque (const rw::math::Vector3D<> &t, rw::kinematics::State &state)
 Adds a force described in parent frame to the center of mass of this body. More...
 
rw::math::Vector3D getTorque (const rw::kinematics::State &state) const
 returns torque described in body frame More...
 
rw::kinematics::FramegetParent (const rw::kinematics::State &state) const
 return the parent frame
 
rw::math::Transform3D getPTBody (const rw::kinematics::State &state) const
 returns the transform from parent to body
 
void setPTBody (const rw::math::Transform3D<> &pTb, rw::kinematics::State &state)
 set the transform of the body. The transform is described relative to parent.
 
rw::math::Transform3D getWTBody (const rw::kinematics::State &state) const
 returns the transform from world to body
 
rw::math::Transform3D getWTParent (const rw::kinematics::State &state) const
 Get the transform from the parent. More...
 
rw::math::Vector3D getLinVel (const rw::kinematics::State &state) const
 return the linear velocity described in parent frame
 
rw::math::Vector3D getLinVelW (const rw::kinematics::State &state) const
 return the linear velocity described in world frame
 
void setLinVel (const rw::math::Vector3D<> &lvel, rw::kinematics::State &state)
 set the linear velocity.
 
void setLinVelW (const rw::math::Vector3D<> &lvel, rw::kinematics::State &state)
 Set the linear velocity in world frame. More...
 
rw::math::Vector3D getAngVel (const rw::kinematics::State &state) const
 returns the angular velocity described in parent frame
 
virtual rw::math::Vector3D getAngVelW (const rw::kinematics::State &state) const
 returns the angular velocity described in world frame
 
virtual void setAngVel (const rw::math::Vector3D<> &avel, rw::kinematics::State &state)
 set the angular velocity of this rigid body.
 
void setAngVelW (const rw::math::Vector3D<> &avel, rw::kinematics::State &state)
 Set the angular velocity in world frame. More...
 
rw::math::Vector3D getPointVel (const rw::math::Vector3D<> &p, const rw::kinematics::State &state)
 calculates the relative velocity in parent frame of a point p on the body described in parent frame.
 
double getMass () const
 returns the mass of this body
 
double getMassInv () const
 returns the inverse of the mass of this body
 
const rw::math::InertiaMatrixgetBodyInertia () const
 returns the body inertia matrix
 
const rw::math::InertiaMatrixgetBodyInertiaInv () const
 return the inverse of the body inertia matrix
 
const std::pair< rw::math::Rotation3D<>, rw::math::Vector3D<> > & getBodyPrincipalInertia () const
 Get the principal inertia of this body. The inertia is described around the center of mass for the principal axes. More...
 
rw::math::InertiaMatrix calcInertiaTensorInv (const rw::kinematics::State &state) const
 returns the inverse of the inertia tensor described in parent frame.
 
rw::math::InertiaMatrix calcInertiaTensor (const rw::kinematics::State &state) const
 returns the inverse of the inertia tensor described in world frame. More...
 
rw::kinematics::MovableFramegetMovableFrame ()
 The the body frame as a movable frame. More...
 
rw::math::InertiaMatrix calcEffectiveMass (const rw::math::Vector3D<> &wPc, const rw::kinematics::State &state) const
 calculates the effective mass of this rigid body seen from the contact point wPc. wPc is described relative to parent frame
 
rw::math::InertiaMatrix calcEffectiveMassW (const rw::math::Vector3D<> &wPc, const rw::kinematics::State &state) const
 calculates the effective mass of this rigid body seen from the contact point wPc. wPc is described relative to world
 
- Public Member Functions inherited from Body
virtual ~Body ()
 Destructor.
 
const std::string & getName () const
 name of body which is the name of the BodyFrame More...
 
rw::kinematics::FramegetBodyFrame () const
 Returns the frame that the bodies dynamic variables are described relative to. More...
 
const std::vector< rw::geometry::Geometry::Ptr > & getGeometry (const rw::kinematics::State &state)
 Get all geometry associated with this body. More...
 
const std::vector< rw::geometry::Geometry::Ptr > & getGeometry ()
 Get all geometry associated with this body. More...
 
const std::vector< rw::kinematics::Frame * > & getFrames ()
 gets all frames that is staticly connected to this Body More...
 
const BodyInfogetInfo () const
 get the body info More...
 
BodyInfogetInfo ()
 retrieve body information More...
 
const std::string & getMaterialID () const
 Material identifier of this object. More...
 
const rw::math::InertiaMatrixgetInertia () const
 get the inertia matrix of this body. The inertia is described around the center of mass and relative to the parent frame. More...
 
BodyChangedEventchangedEvent ()
 Returns StateChangeEvent needed for subscribing and firing the event. More...
 
void setMass (double m)
 Set the mass of the body. More...
 
void setMass (double m, const rw::math::InertiaMatrix<> &inertia)
 Set the mass and inertia of the body. More...
 
void setMass (double m, const rw::math::InertiaMatrix<> &inertia, const rw::math::Vector3D<> &com)
 Set the mass, inertia and center of mass of the body. More...
 
void setObject (rw::models::Object::Ptr obj)
 Replaces object belonging to the body. More...
 
rw::math::Vector3D getLinVelW (const rw::kinematics::State &state) const
 returns the linear velocity described in world frame
 
rw::math::Vector3D getAngVelW (const rw::kinematics::State &state) const
 returns the angular velocity described in world frame
 
virtual rw::kinematics::FramegetParentFrame (const rw::kinematics::State &state) const
 Get the parent frame of this body. More...
 
virtual void setForceW (const rw::math::Vector3D<> &f, rw::kinematics::State &state)
 Sets the force described in world frame acting on the center mass of this body. More...
 
virtual rw::math::Vector3D getForceW (const rw::kinematics::State &state) const
 Gets the force described in world frame acting on the center mass of this body.
 
virtual void addForceW (const rw::math::Vector3D<> &force, rw::kinematics::State &state)
 Adds a force described in world frame to the center of mass of this body.
 
void addForceToPos (const rw::math::Vector3D<> &force, const rw::math::Vector3D<> &pos, rw::kinematics::State &state)
 Adds a force described in parent frame to this body which is working on a specific position pos that is described relative to this body.
 
virtual void addForceWToPosW (const rw::math::Vector3D<> &force, const rw::math::Vector3D<> &pos, rw::kinematics::State &state)
 Adds a force described in world frame to this body which is worked on a specific position pos that is described relative to world.
 
virtual void setTorqueW (const rw::math::Vector3D<> &t, rw::kinematics::State &state)
 set the torque of this body with torque t, where t is described in world frame
 
virtual void addTorqueW (const rw::math::Vector3D<> &t, rw::kinematics::State &state)
 Add a torque to the body. More...
 
virtual rw::math::Vector3D getTorqueW (const rw::kinematics::State &state) const
 returns torque described in world frame
 
virtual rw::math::Transform3D getTransformW (const rw::kinematics::State &state) const
 Get the current position and orientation of the body frame relative to world frame. More...
 
rw::math::Transform3D pTbf (const rw::kinematics::State &state) const
 Get the current position and orientation of the body frame relative to the body parent frame. More...
 
rw::math::Transform3D pTcom (const rw::kinematics::State &state) const
 Get the current position of the body center of mass relative to the body parent frame. More...
 
rw::math::Transform3D wTbf (const rw::kinematics::State &state) const
 Get the current position and orientation of the body frame relative to world frame. More...
 
rw::math::Transform3D wTcom (const rw::kinematics::State &state) const
 Get the current position of the body center of mass relative to the world frame. More...
 
rw::models::Object::Ptr getObject () const
 Get the geometry information for the body. More...
 
- Public Member Functions inherited from Stateless
virtual ~Stateless ()
 destructor
 
virtual void registerIn (State &state)
 initialize this stateless data to a specific state More...
 
virtual void registerIn (StateStructure::Ptr state)
 register this stateless object in a statestructure.
 
virtual void unregister ()
 unregisters all state data of this stateless object
 
StateStructure::Ptr getStateStructure ()
 Get the state structure. More...
 
const StateStructure::Ptr getStateStructure () const
 Get the state structure. More...
 
bool isRegistered ()
 Check if object has registered its state. More...
 

Protected Attributes

const double _mass
 Mass of the body.
 
const double _massInv
 The inverse of the mass of the body.
 
rw::kinematics::MovableFrame_mframe
 The body frame.
 
const rw::math::InertiaMatrix _Ibody
 Inertia of the body.
 
const rw::math::InertiaMatrix _IbodyInv
 Inverse of the inertia of the body.
 
const std::pair< rw::math::Rotation3D<>, rw::math::Vector3D<> > _IbodyPrincipal
 The principal inertia as a rotation and a vector giving the diagonal.
 
rw::math::InertiaMatrix _ITensorInv
 Inertia tensor in parent frame.
 
rw::math::InertiaMatrix __ITensor
 Inverse inertia tensor in parent frame.
 
rw::kinematics::StatelessData< RigidBodyState_rstate
 The state of the rigid body.
 
- Protected Attributes inherited from Body
BodyInfo _info
 The dynamic parameters for the body.
 
- Protected Attributes inherited from Stateless
bool _registered
 True if object has registered its state.
 
std::vector< rw::core::Ptr< StateData > > _datas
 Data.
 
StateStructure::Ptr _stateStruct
 The state structure.
 

Additional Inherited Members

- Public Attributes inherited from Body
BodyChangedEvent _bodyChangedEvent
 The event where listeners can be registered.
 
- Protected Member Functions inherited from Body
 Body (const BodyInfo &info, rw::models::Object::Ptr obj)
 Construct a new dynamic body. More...
 
- Protected Member Functions inherited from Stateless
 Stateless ()
 constructor
 
template<class T >
void add (StatelessData< T > &data)
 implementations of sensor should add all their stateless data on initialization
 
void add (StateData *data)
 Add data. More...
 
void add (rw::core::Ptr< StateData > data)
 implementations of sensor should add all their state data on initialization
 

Detailed Description

A body is an abstraction over some physical object in the scene. The body class is an abstract class that allows interaction by adding gravity, forces and impulses. The integration scheme used to update the velocity and position of the body is defined by the class that inherit the body interface.

The rigid body hold 12 state variables in the StateStructure beside the 6 allocated by MovableFrame (for position). the first 6 state variables are for velocity(linear,angular), and the last six are for force/torque accumulation (force,torque)

Constructor & Destructor Documentation

◆ RigidBody()

RigidBody ( const BodyInfo info,
rw::models::Object::Ptr  obj 
)

Construct a new dynamic body.

Parameters
info[in] general information about the dynamic properties of this body.
obj[in] information about the body reference frame and geometry.

Member Function Documentation

◆ addForce()

void addForce ( const rw::math::Vector3D<> &  force,
rw::kinematics::State state 
)
inlinevirtual

Adds a force described in parent frame to the center of mass of this body.

Implements Body.

◆ addTorque()

void addTorque ( const rw::math::Vector3D<> &  t,
rw::kinematics::State state 
)
inlinevirtual

Adds a force described in parent frame to the center of mass of this body.

Implements Body.

◆ calcEnergy()

double calcEnergy ( const rw::kinematics::State state,
const rw::math::Vector3D<> &  gravity = rw::math::Vector3D<>::zero(),
const rw::math::Vector3D<> &  potZero = rw::math::Vector3D<>::zero() 
) const
virtual

Calculates the total energy of the body.

Parameters
state[in] the state with position and velocity of the body.
gravity[in] (optional) the gravity to use for calculation of potential energy
  • if not specified, no potential energy is calculated.
potZero[in] (optional) the zero point for calculation of potential energy.
Returns
the total energy of the body.
Note
RigidBody energy is calculated as \( \frac12 m \mathbf{v}^2 + \frac12 \mathbf{I} \mathbf{w} \cdot \mathbf{w} - m \mathbf{g} \cdot (\mathbf{p}-\mathbf{p_0}) \)

Implements Body.

◆ calcInertiaTensor()

rw::math::InertiaMatrix calcInertiaTensor ( const rw::kinematics::State state) const

returns the inverse of the inertia tensor described in world frame.

returns the inverse of the inertia tensor described in parent frame.

◆ getBodyPrincipalInertia()

const std::pair<rw::math::Rotation3D<>, rw::math::Vector3D<> >& getBodyPrincipalInertia ( ) const
inline

Get the principal inertia of this body. The inertia is described around the center of mass for the principal axes.

Returns
the principal inertia and the principal axes as a rotation matrix.

◆ getForce()

rw::math::Vector3D getForce ( const rw::kinematics::State state) const
inlinevirtual

Gets the force described in parent frame acting on the center mass of this body.

Implements Body.

◆ getMovableFrame()

rw::kinematics::MovableFrame* getMovableFrame ( )
inline

The the body frame as a movable frame.

Returns
a pointer to a movable frame.

◆ getPointVelW()

rw::math::Vector3D getPointVelW ( const rw::math::Vector3D<> &  p,
const rw::kinematics::State state 
) const
virtual

calculates the relative velocity of a point p on the body described in world frames.

Reimplemented from Body.

◆ getTorque()

rw::math::Vector3D getTorque ( const rw::kinematics::State state) const
inlinevirtual

returns torque described in body frame

Implements Body.

◆ getVelocity()

rw::math::VelocityScrew6D getVelocity ( const rw::kinematics::State state) const
virtual

gets the velocity of this body relative to the parent frame

Parameters
state
Returns

Implements Body.

◆ getWTParent()

rw::math::Transform3D getWTParent ( const rw::kinematics::State state) const
inline

Get the transform from the parent.

Parameters
state[in] the state giving the current pose of the body.
Returns
the relative transform.

◆ reset()

void reset ( rw::kinematics::State state)
virtual

reset the state variables of this body

Implements Body.

◆ setAngVelW()

void setAngVelW ( const rw::math::Vector3D<> &  avel,
rw::kinematics::State state 
)
inline

Set the angular velocity in world frame.

Parameters
avel[in] the angular velocity.
state[out] the state with the current pose, updated with new velocity.

◆ setForce()

void setForce ( const rw::math::Vector3D<> &  f,
rw::kinematics::State state 
)
inlinevirtual

Sets the force described in parent frame acting on the center mass of this body.

Implements Body.

◆ setLinVelW()

void setLinVelW ( const rw::math::Vector3D<> &  lvel,
rw::kinematics::State state 
)
inline

Set the linear velocity in world frame.

Parameters
lvel[in] the linear velocity.
state[out] the state with the current pose, updated with new velocity.

◆ setTorque()

void setTorque ( const rw::math::Vector3D<> &  t,
rw::kinematics::State state 
)
inlinevirtual

set the torque of this body with torque t, where t is described in body frame

Implements Body.


The documentation for this class was generated from the following file: