RobWorkProject  23.9.11-
Public Types | Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | List of all members
Body Class Referenceabstract

The body interface describe the basic interface of some physical entity in the virtual world. That is as a minimum the body has a geometric description, and a material identity. More...

#include <Body.hpp>

Inherits Stateless.

Inherited by BeamBody, FixedBody, FixedLink, KinematicBody, Link, and RigidBody.

Public Types

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

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...
 
virtual 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.
 
virtual rw::math::VelocityScrew6D getVelocity (const rw::kinematics::State &state) const =0
 gets the velocity of this body relative to the parent frame More...
 
virtual rw::math::Vector3D getLinVel (const rw::kinematics::State &state) const
 returns the linear velocity described in parent frame
 
virtual rw::math::Vector3D getAngVel (const rw::kinematics::State &state) const
 returns the angular velocity described in parent frame
 
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 void reset (rw::kinematics::State &state)=0
 reset the state variables of this body
 
virtual 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 =0
 Calculates the total energy of the body. More...
 
virtual void setForce (const rw::math::Vector3D<> &f, rw::kinematics::State &state)=0
 Sets the force described in parent frame acting on the center mass of this body.
 
virtual rw::math::Vector3D getForce (const rw::kinematics::State &state) const =0
 Gets the force described in parent frame acting on the center mass of this body.
 
virtual void addForce (const rw::math::Vector3D<> &force, rw::kinematics::State &state)=0
 Adds a force described in parent frame to the center of mass of this body.
 
virtual void setTorque (const rw::math::Vector3D<> &t, rw::kinematics::State &state)=0
 set the torque of this body with torque t, where t is described in body frame
 
virtual void addTorque (const rw::math::Vector3D<> &t, rw::kinematics::State &state)=0
 Adds a force described in parent frame to the center of mass of this body.
 
virtual rw::math::Vector3D getTorque (const rw::kinematics::State &state) const =0
 returns torque described in body 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...
 

Public Attributes

BodyChangedEvent _bodyChangedEvent
 The event where listeners can be registered.
 

Protected Member Functions

 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
 

Protected Attributes

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.
 

Detailed Description

The body interface describe the basic interface of some physical entity in the virtual world. That is as a minimum the body has a geometric description, and a material identity.

The body interface is used to add impulses, calculate basic velocity stuff and saving/updating the velocity and position states.

Member Typedef Documentation

◆ BodyChangedListener

typedef boost::function<void(BodyEventType)> BodyChangedListener

Defines a state changed listener.

Listeners to this event is called when a change of the state occurs.

StateChangedListener describes the signature of a callback method.

Example usage in a plugin:

void MyPlugin::initialize()
{
getRobWorkStudio()->stateChangedEvent().add(
boost::bind(&MyPlugin::stateChangedListener, this, boost::arg<1>()), this);
}
void MyPlugin::stateChangedListener(const State& state)
{
...
}

Member Enumeration Documentation

◆ BodyEventType

Types of events a body can emit.

Enumerator
MassChangedEvent 

If mass, inertia or center of mass of a body is changed.

Constructor & Destructor Documentation

◆ Body()

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

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

◆ addTorqueW()

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

Add a torque to the body.

Parameters
t[in] the torque to add, described in world frame.
state[in] the state giving the current pose of the object relative to the world frame.

◆ calcEnergy()

virtual 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
pure 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.

Implemented in RigidBody, Link, KinematicBody, FixedBody, and BeamBody.

◆ changedEvent()

BodyChangedEvent& changedEvent ( )
inline

Returns StateChangeEvent needed for subscribing and firing the event.

Returns
Reference to the StateChangedEvent

◆ getBodyFrame()

rw::kinematics::Frame* getBodyFrame ( ) const
inline

Returns the frame that the bodies dynamic variables are described relative to.

Returns
pointer to the body reference frame.

◆ getFrames()

const std::vector<rw::kinematics::Frame*>& getFrames ( )
inline

gets all frames that is staticly connected to this Body

Returns
list of frames

◆ getGeometry() [1/2]

const std::vector<rw::geometry::Geometry::Ptr>& getGeometry ( )
inline

Get all geometry associated with this body.

Returns
a vector of all geometries for the body.
Deprecated:
please use getGeometry(rw::kinematics::State&) instead.

◆ getGeometry() [2/2]

const std::vector<rw::geometry::Geometry::Ptr>& getGeometry ( const rw::kinematics::State state)
inline

Get all geometry associated with this body.

Parameters
state[in] the current state (for deformable bodies).
Returns
a vector of all geometries for the body.

◆ getInertia()

const rw::math::InertiaMatrix& getInertia ( ) const
inline

get the inertia matrix of this body. The inertia is described around the center of mass and relative to the parent frame.

Returns
the inertia matrix.

◆ getInfo() [1/2]

BodyInfo& getInfo ( )
inline

retrieve body information

Returns
the body information.
Note
changing this will not force a changed event.

◆ getInfo() [2/2]

const BodyInfo& getInfo ( ) const
inline

get the body info

Returns
the body info.

◆ getMaterialID()

const std::string& getMaterialID ( ) const
inline

Material identifier of this object.

Returns
the identifier.

◆ getName()

const std::string& getName ( ) const
inline

name of body which is the name of the BodyFrame

Returns
the name.

◆ getObject()

rw::models::Object::Ptr getObject ( ) const
inline

Get the geometry information for the body.

Returns
the object.

◆ getParentFrame()

virtual rw::kinematics::Frame* getParentFrame ( const rw::kinematics::State state) const
inlinevirtual

Get the parent frame of this body.

Parameters
state[in] the state.
Returns
a pointer to the parent frame.

◆ getTransformW()

virtual rw::math::Transform3D getTransformW ( const rw::kinematics::State state) const
inlinevirtual

Get the current position and orientation of the body frame relative to world frame.

Parameters
state[in] the state giving the current pose.
Returns
the pose of the body frame relative to the world frame.

◆ getVelocity()

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

gets the velocity of this body relative to the parent frame

Parameters
state
Returns

Implemented in RigidBody, Link, KinematicBody, and FixedBody.

◆ pTbf()

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

Get the current position and orientation of the body frame relative to the body parent frame.

Parameters
state[in] the state giving the current pose.
Returns
the pose of the body frame relative to the body parent frame.

◆ pTcom()

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

Get the current position of the body center of mass relative to the body parent frame.

Parameters
state[in] the state giving the current pose.
Returns
the position of the body center of mass relative to the body parent frame.

◆ setForceW()

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

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

Note
more efficient to use setForce()

◆ setMass() [1/3]

void setMass ( double  m)
inline

Set the mass of the body.

Note
a BodyChangedEvent is fired.
Parameters
m[in] the new mass of the body.

◆ setMass() [2/3]

void setMass ( double  m,
const rw::math::InertiaMatrix<> &  inertia 
)
inline

Set the mass and inertia of the body.

Note
a BodyChangedEvent is fired.
Parameters
m[in] the new mass of the body.
inertia[in] the new inertia of the body.

◆ setMass() [3/3]

void setMass ( double  m,
const rw::math::InertiaMatrix<> &  inertia,
const rw::math::Vector3D<> &  com 
)
inline

Set the mass, inertia and center of mass of the body.

Note
a BodyChangedEvent is fired.
Parameters
m[in] the new mass of the body.
inertia[in] the new inertia of the body.
com[in] the new center of mass.

◆ setObject()

void setObject ( rw::models::Object::Ptr  obj)

Replaces object belonging to the body.

Geometry is replaced.

Warning
BodyInfo is not changed! This has to be done manually.
Todo:
Make BodyInfo adjust automatically.
Parameters
obj[in] the new object.

◆ wTbf()

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

Get the current position and orientation of the body frame relative to world frame.

Parameters
state[in] the state giving the current pose.
Returns
the pose of the body frame relative to the world frame.
Note
This is equivalent to getTransformW()

◆ wTcom()

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

Get the current position of the body center of mass relative to the world frame.

Parameters
state[in] the state giving the current pose.
Returns
the position of the body center of mass relative to the world frame.

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