Ravelin
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
ARTICULATED_BODY Class Referenceabstract

Abstract class for articulated bodies. More...

#include <ArticulatedBody.h>

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

Public Member Functions

virtual bool is_floating_base () const =0
 
virtual boost::shared_ptr
< RIGIDBODY
get_base_link () const =0
 
unsigned num_constraint_eqns_explicit () const
 Gets the number of explicit joint constraint equations.
 
unsigned num_constraint_eqns_implicit () const
 Gets the number of implicit joint constraint equations.
 
virtual void rotate (const QUAT &q)
 Transforms all links in the articulated body by the given transform. More...
 
virtual void translate (const ORIGIN3 &o)
 Transforms all links in the articulated body by the given transform. More...
 
virtual REAL calc_kinetic_energy (boost::shared_ptr< const POSE3 > P=boost::shared_ptr< const POSE3 >())
 Calculates the combined kinetic energy of all links in this body with respect to the base frame.
 
boost::shared_ptr< RIGIDBODYfind_link (const std::string &id) const
 
boost::shared_ptr< JOINTfind_joint (const std::string &id) const
 
void get_adjacent_links (std::list< sorted_pair< boost::shared_ptr< RIGIDBODY > > > &links) const
 
virtual void set_links_and_joints (const std::vector< boost::shared_ptr< RIGIDBODY > > &links, const std::vector< boost::shared_ptr< JOINT > > &joints)
 
virtual unsigned num_joint_dof () const
 Gets the number of joint degrees of freedom permitted by both implicit and explicit joint constraints.
 
void find_loops (std::vector< unsigned > &loop_indices, std::vector< std::vector< unsigned > > &loop_links) const
 
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)
 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)
 
virtual MATRIXNcalc_jacobian (boost::shared_ptr< const POSE3 > target_pose, boost::shared_ptr< DYNAMIC_BODY > body, MATRIXN &J)
 
virtual MATRIXNcalc_jacobian_dot (boost::shared_ptr< const POSE3 > target_pose, boost::shared_ptr< DYNAMIC_BODY > body, MATRIXN &J)
 
virtual bool is_enabled () const
 Articulated bodies are always enabled.
 
virtual unsigned num_joint_dof_explicit () const =0
 Gets the number of degrees-of-freedom permitted by explicit constraints.
 
virtual unsigned num_joint_dof_implicit () const =0
 Gets the number of degrees-of-freedom permitted by implicit constraints.
 
virtual const std::vector
< boost::shared_ptr< RIGIDBODY > > & 
get_links () const
 Gets the set of links.
 
virtual const std::vector
< boost::shared_ptr< JOINT > > & 
get_joints () const
 Gets the set of joints.
 
virtual const std::vector
< boost::shared_ptr< JOINT > > & 
get_explicit_joints () const =0
 Gets the set of explicit joints.
 
virtual const std::vector
< boost::shared_ptr< JOINT > > & 
get_implicit_joints () const =0
 Gets the set of implicit joints.
 
boost::shared_ptr
< ARTICULATED_BODY
get_this ()
 Gets shared pointer to this object as type ARTICULATED_BODY.
 
boost::shared_ptr< const
ARTICULATED_BODY
get_this () const
 Gets shared pointer to this object as type const ArticulateBody.
 
virtual void apply_impulse (const SMOMENTUM &w, boost::shared_ptr< RIGIDBODY > link)=0
 Abstract method for applying an impulse to this articulated body. More...
 
virtual void reset_accumulators ()=0
 Method for resetting the force and torque accumulators on all links. More...
 
- Public Member Functions inherited from DYNAMIC_BODY
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 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
 

Protected Member Functions

virtual void compile ()
 Method for "compiling" the body. More...
 

Protected Attributes

std::vector< unsigned > _processed
 Vector for processing links.
 
std::vector< boost::shared_ptr
< RIGIDBODY > > 
_links
 The set of links for this articulated body.
 
std::vector< boost::shared_ptr
< JOINT > > 
_joints
 The set of joints for this articulated body.
 
- Protected Attributes inherited from DYNAMIC_BODY
ReferenceFrameType _rftype
 The computation frame type.
 
VECTORN gc
 Temporaries for use with integration.
 
VECTORN gv
 
VECTORN gcgv
 
VECTORN xp
 
VECTORN xv
 
VECTORN xa
 

Additional Inherited Members

- Public Types inherited from DYNAMIC_BODY
enum  GeneralizedCoordinateType { eEuler, eSpatial }
 
- Public Attributes inherited from DYNAMIC_BODY
std::string body_id
 The identifier for this body.
 

Detailed Description

Abstract class for articulated bodies.

Member Function Documentation

virtual void ARTICULATED_BODY::apply_impulse ( const SMOMENTUM w,
boost::shared_ptr< RIGIDBODY link 
)
pure virtual

Abstract method for applying an impulse to this articulated body.

Parameters
wthe impulsive force
linklink in the articulated body where the impulse is applied

Implemented in RC_ARTICULATED_BODY.

void ARTICULATED_BODY::compile ( )
protectedvirtual

Method for "compiling" the body.

"Compiles" the articulated body

Compilation is necessary anytime the structure or topolgy of the body changes. Generally, this will only be necessary once - after a call to set_links() or set_joints().

Reimplemented in RC_ARTICULATED_BODY.

Referenced by RC_ARTICULATED_BODY::compile().

void ARTICULATED_BODY::reset_accumulators ( )
pure virtual

Method for resetting the force and torque accumulators on all links.

Resets force and torque accumulators on the body.

Force and torque accumulators on all links are reset.

Implements DYNAMIC_BODY.

Implemented in RC_ARTICULATED_BODY.

References _links.

void ARTICULATED_BODY::rotate ( const QUAT q)
virtual

Transforms all links in the articulated body by the given transform.

The given transformation is cumulative; the links will not necessarily be set to T.

Implements DYNAMIC_BODY.

References _links.

void ARTICULATED_BODY::translate ( const ORIGIN3 x)
virtual

Transforms all links in the articulated body by the given transform.

The given transformation is cumulative; the links will not necessarily be set to T.

Implements DYNAMIC_BODY.

References _links.


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