Ravelin
Public Types | Public Member Functions | Public Attributes | Protected Attributes | List of all members
Ravelin::DYNAMIC_BODY Class Referenceabstract

Superclass for deformable bodies and single and multi-rigid bodies. More...

#include <DynamicBodyd.h>

Inheritance diagram for Ravelin::DYNAMIC_BODY:
Ravelin::virtual_enable_shared_from_this< DYNAMIC_BODY > Ravelin::virtual_enable_shared_from_this< DYNAMIC_BODY > Ravelin::virtual_enable_shared_from_this_base Ravelin::virtual_enable_shared_from_this_base Ravelin::ARTICULATED_BODY Ravelin::ARTICULATED_BODY Ravelin::SINGLE_BODY Ravelin::SINGLE_BODY Ravelin::RC_ARTICULATED_BODY Ravelin::RC_ARTICULATED_BODY Ravelin::RC_ARTICULATED_BODY Ravelin::RC_ARTICULATED_BODY Ravelin::RIGIDBODY Ravelin::RIGIDBODY Ravelin::RIGIDBODY Ravelin::RIGIDBODY

Public Types

enum  GeneralizedCoordinateType { eEuler, eSpatial, eEuler, eSpatial }
 
enum  GeneralizedCoordinateType { eEuler, eSpatial, eEuler, eSpatial }
 

Public Member Functions

virtual bool is_enabled () const =0
 Gets whether the body's dynamics are integrated forward.
 
virtual MATRIXNcalc_jacobian (boost::shared_ptr< const POSE3 > source_pose, boost::shared_ptr< const POSE3 > target_pose, boost::shared_ptr< DYNAMIC_BODY > body, MATRIXN &J)=0
 The Jacobian transforms from the generalized coordinate from to the given frame.
 
virtual MATRIXNcalc_jacobian_dot (boost::shared_ptr< const POSE3 > source_pose, boost::shared_ptr< const POSE3 > target_pose, boost::shared_ptr< DYNAMIC_BODY > body, MATRIXN &J)=0
 
virtual void validate_position_variables ()
 Validates position-based variables (potentially dangerous for a user to call)
 
virtual void validate_velocity_variables ()
 Validates velocity-based variables (potentially dangerous for a user to call)
 
virtual void set_computation_frame_type (ReferenceFrameType rftype)=0
 Sets the computation frame type for this body.
 
ReferenceFrameType get_computation_frame_type () const
 Gets the computation frame type for this body.
 
virtual void calc_fwd_dyn ()=0
 Forces a recalculation of forward dynamics.
 
virtual void reset_accumulators ()=0
 Resets the force and torque accumulators on the dynamic body.
 
virtual void rotate (const QUAT &q)=0
 Rotates the dynamic body by the given orientation.
 
virtual void translate (const ORIGIN3 &o)=0
 Translates the dynamic body by the given translation.
 
virtual REAL calc_kinetic_energy (boost::shared_ptr< const POSE3 > P=boost::shared_ptr< const POSE3 >())=0
 Calculates the kinetic energy of the body in an arbitrary frame.
 
virtual boost::shared_ptr
< const POSE3
get_gc_pose () const =0
 Gets the frame for generalized coordinates.
 
virtual unsigned num_generalized_coordinates (GeneralizedCoordinateType gctype) const =0
 Gets the number of generalized coordinates.
 
virtual void set_generalized_forces (const SHAREDVECTORN &gf)=0
 Sets the generalized forces on the body.
 
virtual void set_generalized_forces (const VECTORN &gf)
 Sets the generalized forces on the body.
 
virtual void add_generalized_force (const SHAREDVECTORN &gf)=0
 Adds a generalized force to the body.
 
virtual void add_generalized_force (const VECTORN &gf)
 Adds a generalized force to the body.
 
virtual void apply_generalized_impulse (const SHAREDVECTORN &gj)=0
 Applies a generalized impulse to the body.
 
virtual void apply_generalized_impulse (const VECTORN &gj)
 Applies a generalized impulse to the body.
 
virtual SHAREDVECTORNget_generalized_coordinates_euler (SHAREDVECTORN &gc)=0
 Gets the generalized coordinates of this body (using Euler parameters for any rigid body orientations, if relevant)
 
virtual VECTORNget_generalized_coordinates_euler (VECTORN &gc)
 Gets the generalized coordinates of this body (using Euler parameters for any rigid body orientations, if relevant)
 
virtual SHAREDVECTORNget_generalized_velocity (GeneralizedCoordinateType gctype, SHAREDVECTORN &gv)=0
 Gets the generalized velocity of this body.
 
virtual VECTORNget_generalized_velocity (GeneralizedCoordinateType gctype, VECTORN &gv)
 Gets the generalized velocity of this body.
 
virtual void set_generalized_acceleration (const SHAREDVECTORN &ga)=0
 Sets the generalized velocity of this body.
 
virtual void set_generalized_acceleration (const VECTORN &ga)
 Sets the generalized acceleration of this body.
 
virtual SHAREDVECTORNget_generalized_acceleration (SHAREDVECTORN &ga)=0
 Gets the generalized velocity of this body.
 
virtual VECTORNget_generalized_acceleration (VECTORN &ga)
 Gets the generalized acceleration of this body.
 
virtual void set_generalized_coordinates_euler (const SHAREDVECTORN &gc)=0
 Sets the generalized coordinates of this body (using Euler parameters for any rigid body orientations, if relevant)
 
virtual void set_generalized_coordinates_euler (const VECTORN &gc)
 Sets the generalized coordinates of this body (using Euler parameters for any rigid body orientations, if relevant)
 
virtual void set_generalized_velocity (GeneralizedCoordinateType gctype, const SHAREDVECTORN &gv)=0
 Sets the generalized velocity of this body. More...
 
virtual void set_generalized_velocity (GeneralizedCoordinateType gctype, const VECTORN &gv)
 Sets the generalized velocity of this body.
 
MATRIXNget_generalized_inertia (MATRIXN &M)
 Gets the generalized inertia of this body.
 
virtual SHAREDMATRIXNget_generalized_inertia (SHAREDMATRIXN &M)=0
 Gets the generalized inertia of this body.
 
virtual SHAREDMATRIXNsolve_generalized_inertia (const SHAREDMATRIXN &B, SHAREDMATRIXN &X)=0
 Solves using the inverse generalized inertia.
 
virtual MATRIXNsolve_generalized_inertia (const MATRIXN &B, MATRIXN &X)
 Solves using the inverse generalized inertia.
 
virtual MATRIXNsolve_generalized_inertia (const SHAREDMATRIXN &B, MATRIXN &X)
 Solves using the inverse generalized inertia.
 
virtual SHAREDMATRIXNsolve_generalized_inertia (const MATRIXN &B, SHAREDMATRIXN &X)
 Solves using the inverse generalized inertia.
 
virtual VECTORNsolve_generalized_inertia (const VECTORN &b, VECTORN &x)
 Solves using the inverse generalized inertia.
 
virtual VECTORNsolve_generalized_inertia (const SHAREDVECTORN &b, VECTORN &x)
 Solves using the inverse generalized inertia.
 
virtual SHAREDVECTORNsolve_generalized_inertia (const VECTORN &b, SHAREDVECTORN &x)
 Solves using the inverse generalized inertia.
 
virtual SHAREDVECTORNsolve_generalized_inertia (const SHAREDVECTORN &b, SHAREDVECTORN &x)=0
 Solves using the inverse generalized inertia.
 
virtual MATRIXNtranspose_solve_generalized_inertia (const MATRIXN &B, MATRIXN &X)
 Solves the transpose matrix using the inverse generalized inertia.
 
virtual MATRIXNtranspose_solve_generalized_inertia (const SHAREDMATRIXN &B, MATRIXN &X)
 Solves the transpose matrix using the inverse generalized inertia.
 
virtual SHAREDMATRIXNtranspose_solve_generalized_inertia (const MATRIXN &B, SHAREDMATRIXN &X)
 Solves the transpose matrix using the inverse generalized inertia.
 
virtual SHAREDMATRIXNtranspose_solve_generalized_inertia (const SHAREDMATRIXN &B, SHAREDMATRIXN &X)=0
 Solves the transpose matrix using the inverse generalized inertia.
 
virtual SHAREDVECTORNget_generalized_forces (SHAREDVECTORN &f)=0
 Gets the external forces on this body. More...
 
virtual VECTORNget_generalized_forces (VECTORN &f)
 Gets the external forces on this body. More...
 
virtual SHAREDVECTORNconvert_to_generalized_force (boost::shared_ptr< SINGLE_BODY > body, const SFORCE &w, SHAREDVECTORN &gf)=0
 Converts a force to a generalized force. More...
 
virtual VECTORNconvert_to_generalized_force (boost::shared_ptr< SINGLE_BODY > body, const SFORCE &w, VECTORN &gf)
 Converts a force to a generalized force. More...
 
virtual bool is_enabled () const =0
 Gets whether the body's dynamics are integrated forward.
 
virtual MATRIXNcalc_jacobian (boost::shared_ptr< const POSE3 > source_pose, boost::shared_ptr< const POSE3 > target_pose, boost::shared_ptr< DYNAMIC_BODY > body, MATRIXN &J)=0
 The Jacobian transforms from the generalized coordinate from to the given frame.
 
virtual MATRIXNcalc_jacobian_dot (boost::shared_ptr< const POSE3 > source_pose, boost::shared_ptr< const POSE3 > target_pose, boost::shared_ptr< DYNAMIC_BODY > body, MATRIXN &J)=0
 
virtual void validate_position_variables ()
 Validates position-based variables (potentially dangerous for a user to call)
 
virtual void validate_velocity_variables ()
 Validates velocity-based variables (potentially dangerous for a user to call)
 
virtual void set_computation_frame_type (ReferenceFrameType rftype)=0
 Sets the computation frame type for this body.
 
ReferenceFrameType get_computation_frame_type () const
 Gets the computation frame type for this body.
 
virtual void calc_fwd_dyn ()=0
 Forces a recalculation of forward dynamics.
 
virtual void reset_accumulators ()=0
 Resets the force and torque accumulators on the dynamic body.
 
virtual void rotate (const QUAT &q)=0
 Rotates the dynamic body by the given orientation.
 
virtual void translate (const ORIGIN3 &o)=0
 Translates the dynamic body by the given translation.
 
virtual REAL calc_kinetic_energy (boost::shared_ptr< const POSE3 > P=boost::shared_ptr< const POSE3 >())=0
 Calculates the kinetic energy of the body in an arbitrary frame.
 
virtual boost::shared_ptr
< const POSE3
get_gc_pose () const =0
 Gets the frame for generalized coordinates.
 
virtual unsigned num_generalized_coordinates (GeneralizedCoordinateType gctype) const =0
 Gets the number of generalized coordinates.
 
virtual void set_generalized_forces (const SHAREDVECTORN &gf)=0
 Sets the generalized forces on the body.
 
virtual void set_generalized_forces (const VECTORN &gf)
 Sets the generalized forces on the body.
 
virtual void add_generalized_force (const SHAREDVECTORN &gf)=0
 Adds a generalized force to the body.
 
virtual void add_generalized_force (const VECTORN &gf)
 Adds a generalized force to the body.
 
virtual void apply_generalized_impulse (const SHAREDVECTORN &gj)=0
 Applies a generalized impulse to the body.
 
virtual void apply_generalized_impulse (const VECTORN &gj)
 Applies a generalized impulse to the body.
 
virtual SHAREDVECTORNget_generalized_coordinates_euler (SHAREDVECTORN &gc)=0
 Gets the generalized coordinates of this body (using Euler parameters for any rigid body orientations, if relevant)
 
virtual VECTORNget_generalized_coordinates_euler (VECTORN &gc)
 Gets the generalized coordinates of this body (using Euler parameters for any rigid body orientations, if relevant)
 
virtual SHAREDVECTORNget_generalized_velocity (GeneralizedCoordinateType gctype, SHAREDVECTORN &gv)=0
 Gets the generalized velocity of this body.
 
virtual VECTORNget_generalized_velocity (GeneralizedCoordinateType gctype, VECTORN &gv)
 Gets the generalized velocity of this body.
 
virtual void set_generalized_acceleration (const SHAREDVECTORN &ga)=0
 Sets the generalized velocity of this body.
 
virtual void set_generalized_acceleration (const VECTORN &ga)
 Sets the generalized acceleration of this body.
 
virtual SHAREDVECTORNget_generalized_acceleration (SHAREDVECTORN &ga)=0
 Gets the generalized velocity of this body.
 
virtual VECTORNget_generalized_acceleration (VECTORN &ga)
 Gets the generalized acceleration of this body.
 
virtual void set_generalized_coordinates_euler (const SHAREDVECTORN &gc)=0
 Sets the generalized coordinates of this body (using Euler parameters for any rigid body orientations, if relevant)
 
virtual void set_generalized_coordinates_euler (const VECTORN &gc)
 Sets the generalized coordinates of this body (using Euler parameters for any rigid body orientations, if relevant)
 
virtual void set_generalized_velocity (GeneralizedCoordinateType gctype, const SHAREDVECTORN &gv)=0
 Sets the generalized velocity of this body. More...
 
virtual void set_generalized_velocity (GeneralizedCoordinateType gctype, const VECTORN &gv)
 Sets the generalized velocity of this body.
 
MATRIXNget_generalized_inertia (MATRIXN &M)
 Gets the generalized inertia of this body.
 
virtual SHAREDMATRIXNget_generalized_inertia (SHAREDMATRIXN &M)=0
 Gets the generalized inertia of this body.
 
virtual SHAREDMATRIXNsolve_generalized_inertia (const SHAREDMATRIXN &B, SHAREDMATRIXN &X)=0
 Solves using the inverse generalized inertia.
 
virtual MATRIXNsolve_generalized_inertia (const MATRIXN &B, MATRIXN &X)
 Solves using the inverse generalized inertia.
 
virtual MATRIXNsolve_generalized_inertia (const SHAREDMATRIXN &B, MATRIXN &X)
 Solves using the inverse generalized inertia.
 
virtual SHAREDMATRIXNsolve_generalized_inertia (const MATRIXN &B, SHAREDMATRIXN &X)
 Solves using the inverse generalized inertia.
 
virtual VECTORNsolve_generalized_inertia (const VECTORN &b, VECTORN &x)
 Solves using the inverse generalized inertia.
 
virtual VECTORNsolve_generalized_inertia (const SHAREDVECTORN &b, VECTORN &x)
 Solves using the inverse generalized inertia.
 
virtual SHAREDVECTORNsolve_generalized_inertia (const VECTORN &b, SHAREDVECTORN &x)
 Solves using the inverse generalized inertia.
 
virtual SHAREDVECTORNsolve_generalized_inertia (const SHAREDVECTORN &b, SHAREDVECTORN &x)=0
 Solves using the inverse generalized inertia.
 
virtual MATRIXNtranspose_solve_generalized_inertia (const MATRIXN &B, MATRIXN &X)
 Solves the transpose matrix using the inverse generalized inertia.
 
virtual MATRIXNtranspose_solve_generalized_inertia (const SHAREDMATRIXN &B, MATRIXN &X)
 Solves the transpose matrix using the inverse generalized inertia.
 
virtual SHAREDMATRIXNtranspose_solve_generalized_inertia (const MATRIXN &B, SHAREDMATRIXN &X)
 Solves the transpose matrix using the inverse generalized inertia.
 
virtual SHAREDMATRIXNtranspose_solve_generalized_inertia (const SHAREDMATRIXN &B, SHAREDMATRIXN &X)=0
 Solves the transpose matrix using the inverse generalized inertia.
 
virtual SHAREDVECTORNget_generalized_forces (SHAREDVECTORN &f)=0
 Gets the external forces on this body. More...
 
virtual VECTORNget_generalized_forces (VECTORN &f)
 Gets the external forces on this body. More...
 
virtual SHAREDVECTORNconvert_to_generalized_force (boost::shared_ptr< SINGLE_BODY > body, const SFORCE &w, SHAREDVECTORN &gf)=0
 Converts a force to a generalized force. More...
 
virtual VECTORNconvert_to_generalized_force (boost::shared_ptr< SINGLE_BODY > body, const SFORCE &w, VECTORN &gf)
 Converts a force to a generalized force. More...
 
- Public Member Functions inherited from Ravelin::virtual_enable_shared_from_this< DYNAMIC_BODY >
boost::shared_ptr< DYNAMIC_BODYshared_from_this ()
 
boost::shared_ptr< const
DYNAMIC_BODY
shared_from_this () const
 

Public Attributes

std::string body_id
 The identifier for this body.
 

Protected Attributes

ReferenceFrameType _rftype
 The computation frame type.
 
VECTORN gc
 Temporaries for use with integration.
 
VECTORN gv
 
VECTORN gcgv
 
VECTORN xp
 
VECTORN xv
 
VECTORN xa
 

Detailed Description

Superclass for deformable bodies and single and multi-rigid bodies.

Member Function Documentation

virtual SHAREDVECTORN& Ravelin::DYNAMIC_BODY::convert_to_generalized_force ( boost::shared_ptr< SINGLE_BODY body,
const SFORCE w,
SHAREDVECTORN gf 
)
pure virtual

Converts a force to a generalized force.

Parameters
bodythe actual rigid body to which the force/torque is applied (at the center-of-mass)
wthe force
gfthe generalized force, on return
Note
uses the current generalized coordinates

Implemented in Ravelin::RIGIDBODY, Ravelin::RIGIDBODY, Ravelin::RC_ARTICULATED_BODY, and Ravelin::RC_ARTICULATED_BODY.

virtual SHAREDVECTORN& Ravelin::DYNAMIC_BODY::convert_to_generalized_force ( boost::shared_ptr< SINGLE_BODY body,
const SFORCE w,
SHAREDVECTORN gf 
)
pure virtual

Converts a force to a generalized force.

Parameters
bodythe actual rigid body to which the force/torque is applied (at the center-of-mass)
wthe force
gfthe generalized force, on return
Note
uses the current generalized coordinates

Implemented in Ravelin::RIGIDBODY, Ravelin::RIGIDBODY, Ravelin::RC_ARTICULATED_BODY, and Ravelin::RC_ARTICULATED_BODY.

virtual VECTORN& Ravelin::DYNAMIC_BODY::convert_to_generalized_force ( boost::shared_ptr< SINGLE_BODY body,
const SFORCE w,
VECTORN gf 
)
inlinevirtual

Converts a force to a generalized force.

Parameters
bodythe actual rigid body to which the force/torque is applied (at the center-of-mass)
wthe force
gfthe generalized force, on return
Note
uses the current generalized coordinates

Reimplemented in Ravelin::RIGIDBODY, Ravelin::RIGIDBODY, Ravelin::RC_ARTICULATED_BODY, and Ravelin::RC_ARTICULATED_BODY.

virtual VECTORN& Ravelin::DYNAMIC_BODY::convert_to_generalized_force ( boost::shared_ptr< SINGLE_BODY body,
const SFORCE w,
VECTORN gf 
)
inlinevirtual

Converts a force to a generalized force.

Parameters
bodythe actual rigid body to which the force/torque is applied (at the center-of-mass)
wthe force
gfthe generalized force, on return
Note
uses the current generalized coordinates

Reimplemented in Ravelin::RIGIDBODY, Ravelin::RIGIDBODY, Ravelin::RC_ARTICULATED_BODY, and Ravelin::RC_ARTICULATED_BODY.

virtual SHAREDVECTORN& Ravelin::DYNAMIC_BODY::get_generalized_forces ( SHAREDVECTORN f)
pure virtual

Gets the external forces on this body.

Note
uses the current generalized coordinates

Implemented in Ravelin::RIGIDBODY, Ravelin::RIGIDBODY, Ravelin::RC_ARTICULATED_BODY, and Ravelin::RC_ARTICULATED_BODY.

virtual SHAREDVECTORN& Ravelin::DYNAMIC_BODY::get_generalized_forces ( SHAREDVECTORN f)
pure virtual

Gets the external forces on this body.

Note
uses the current generalized coordinates

Implemented in Ravelin::RIGIDBODY, Ravelin::RIGIDBODY, Ravelin::RC_ARTICULATED_BODY, and Ravelin::RC_ARTICULATED_BODY.

virtual VECTORN& Ravelin::DYNAMIC_BODY::get_generalized_forces ( VECTORN f)
inlinevirtual

Gets the external forces on this body.

Note
uses the current generalized coordinates

Reimplemented in Ravelin::RIGIDBODY, Ravelin::RIGIDBODY, Ravelin::RC_ARTICULATED_BODY, and Ravelin::RC_ARTICULATED_BODY.

virtual VECTORN& Ravelin::DYNAMIC_BODY::get_generalized_forces ( VECTORN f)
inlinevirtual

Gets the external forces on this body.

Note
uses the current generalized coordinates

Reimplemented in Ravelin::RIGIDBODY, Ravelin::RIGIDBODY, Ravelin::RC_ARTICULATED_BODY, and Ravelin::RC_ARTICULATED_BODY.

virtual void Ravelin::DYNAMIC_BODY::set_generalized_velocity ( GeneralizedCoordinateType  gctype,
const SHAREDVECTORN gv 
)
pure virtual

Sets the generalized velocity of this body.

Parameters
gvthe generalized velocity
Note
uses the current generalized coordinates

Implemented in Ravelin::RIGIDBODY, Ravelin::RIGIDBODY, Ravelin::RC_ARTICULATED_BODY, and Ravelin::RC_ARTICULATED_BODY.

virtual void Ravelin::DYNAMIC_BODY::set_generalized_velocity ( GeneralizedCoordinateType  gctype,
const SHAREDVECTORN gv 
)
pure virtual

Sets the generalized velocity of this body.

Parameters
gvthe generalized velocity
Note
uses the current generalized coordinates

Implemented in Ravelin::RIGIDBODY, Ravelin::RIGIDBODY, Ravelin::RC_ARTICULATED_BODY, and Ravelin::RC_ARTICULATED_BODY.


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