Rigid Body Dynamics Library
|
Contains all information about the rigid body model. More...
Public Member Functions | |
Model () | |
unsigned int | AddBody (const unsigned int parent_id, const Math::SpatialTransform &joint_frame, const Joint &joint, const Body &body, std::string body_name="") |
Connects a given body to the model. More... | |
unsigned int | AddBodySphericalJoint (const unsigned int parent_id, const Math::SpatialTransform &joint_frame, const Joint &joint, const Body &body, std::string body_name="") |
unsigned int | AppendBody (const Math::SpatialTransform &joint_frame, const Joint &joint, const Body &body, std::string body_name="") |
Adds a Body to the model such that the previously added Body is the Parent. More... | |
unsigned int | AddBodyCustomJoint (const unsigned int parent_id, const Math::SpatialTransform &joint_frame, CustomJoint *custom_joint, const Body &body, std::string body_name="") |
unsigned int | GetBodyId (const char *body_name) const |
Returns the id of a body that was passed to AddBody() More... | |
std::string | GetBodyName (unsigned int body_id) const |
Returns the name of a body for a given body id. More... | |
bool | IsFixedBodyId (unsigned int body_id) |
Checks whether the body is rigidly attached to another body. More... | |
bool | IsBodyId (unsigned int id) |
unsigned int | GetParentBodyId (unsigned int id) |
Math::SpatialTransform | GetJointFrame (unsigned int id) |
void | SetJointFrame (unsigned int id, const Math::SpatialTransform &transform) |
Math::Quaternion | GetQuaternion (unsigned int i, const Math::VectorNd &Q) const |
void | SetQuaternion (unsigned int i, const Math::Quaternion &quat, Math::VectorNd &Q) const |
Data Fields | |
std::vector< unsigned int > | lambda |
The id of the parents body. More... | |
std::vector< unsigned int > | lambda_q |
The index of the parent degree of freedom that is directly influencing the current one. More... | |
std::vector< std::vector< unsigned int > > | mu |
Contains the ids of all the children of a given body. More... | |
unsigned int | dof_count |
number of degrees of freedoms of the model More... | |
unsigned int | q_size |
The size of the ![]() ![]() | |
unsigned int | qdot_size |
The size of the. More... | |
unsigned int | previously_added_body_id |
Id of the previously added body, required for Model::AppendBody() More... | |
Math::Vector3d | gravity |
the cartesian vector of the gravity More... | |
std::vector< Math::SpatialVector > | v |
The spatial velocity of the bodies. More... | |
std::vector< Math::SpatialVector > | a |
The spatial acceleration of the bodies. More... | |
std::vector< Joint > | mJoints |
All joints. More... | |
std::vector< Math::SpatialVector > | S |
The joint axis for joint i. More... | |
std::vector< Math::SpatialVector > | v_J |
std::vector< Math::SpatialVector > | c_J |
std::vector< unsigned int > | mJointUpdateOrder |
std::vector< Math::SpatialTransform > | X_T |
Transformations from the parent body to the frame of the joint. More... | |
std::vector< unsigned int > | mFixedJointCount |
The number of fixed joints that have been declared before each joint. More... | |
std::vector< Math::Matrix63 > | multdof3_S |
Motion subspace for joints with 3 degrees of freedom. More... | |
std::vector< Math::Matrix63 > | multdof3_U |
std::vector< Math::Matrix3d > | multdof3_Dinv |
std::vector< Math::Vector3d > | multdof3_u |
std::vector< unsigned int > | multdof3_w_index |
std::vector< CustomJoint * > | mCustomJoints |
std::vector< Math::SpatialVector > | c |
The velocity dependent spatial acceleration. More... | |
std::vector< Math::SpatialMatrix > | IA |
The spatial inertia of the bodies. More... | |
std::vector< Math::SpatialVector > | pA |
The spatial bias force. More... | |
std::vector< Math::SpatialVector > | U |
Temporary variable U_i (RBDA p. 130) More... | |
Math::VectorNd | d |
Temporary variable D_i (RBDA p. 130) More... | |
Math::VectorNd | u |
Temporary variable u (RBDA p. 130) More... | |
std::vector< Math::SpatialVector > | f |
Internal forces on the body (used only InverseDynamics()) More... | |
std::vector< Math::SpatialRigidBodyInertia > | I |
The spatial inertia of body i (used only in CompositeRigidBodyAlgorithm()) More... | |
std::vector< Math::SpatialRigidBodyInertia > | Ic |
std::vector< Math::SpatialVector > | hc |
std::vector< Math::SpatialVector > | hdotc |
std::vector< Math::SpatialTransform > | X_lambda |
Transformation from the parent body to the current body
. More... | |
std::vector< Math::SpatialTransform > | X_base |
Transformation from the base to bodies reference frame. More... | |
std::vector< FixedBody > | mFixedBodies |
All bodies that are attached to a body via a fixed joint. More... | |
unsigned int | fixed_body_discriminator |
Value that is used to discriminate between fixed and movable bodies. More... | |
std::vector< Body > | mBodies |
All bodies 0 ... N_B, including the base. More... | |
std::map< std::string, unsigned int > | mBodyNameMap |
Human readable names for the bodies. More... | |
Contains all information about the rigid body model.
This class contains all information required to perform the forward dynamics calculation. The variables in this class are also used for storage of temporary values. It is designed for use of the Articulated Rigid Body Algorithm (which is implemented in ForwardDynamics()) and follows the numbering as described in Featherstones book.
Please note that body 0 is the root body and the moving bodies start at index 1. This numbering scheme is very beneficial in terms of readability of the code as the resulting code is very similar to the pseudo-code in the RBDA book. The generalized variables q, qdot, qddot and tau however start at 0 such that the first entry (e.g. q[0]) always specifies the value for the first moving body.
unsigned int AddBody | ( | const unsigned int | parent_id, |
const Math::SpatialTransform & | joint_frame, | ||
const Joint & | joint, | ||
const Body & | body, | ||
std::string | body_name = "" |
||
) |
Connects a given body to the model.
When adding a body there are basically informations required:
The first information "what kind of body will be added" is contained in the Body class that is given as a parameter.
The question "where is the new body to be added?" is split up in two parts: first the parent (or successor) body to which it is added and second the transformation to the origin of the joint that connects the two bodies. With these two informations one specifies the relative positions of the bodies when the joint is in neutral position.gk
The last question "by what kind of joint should the body be added?" is again simply contained in the Joint class.
parent_id | id of the parent body |
joint_frame | the transformation from the parent frame to the origin of the joint frame (represents X_T in RBDA) |
joint | specification for the joint that describes the connection |
body | specification of the body itself |
body_name | human readable name for the body (can be used to retrieve its id with GetBodyId()) |
Definition at line 249 of file Model.cc.
References AddBodyFixedJoint(), AddBodyMultiDofJoint(), SpatialRigidBodyInertia::createFromMassComInertiaC(), RigidBodyDynamics::JointTypeCustom, RigidBodyDynamics::JointTypeEulerXYZ, RigidBodyDynamics::JointTypeEulerYXZ, RigidBodyDynamics::JointTypeEulerZXY, RigidBodyDynamics::JointTypeEulerZYX, RigidBodyDynamics::JointTypeFixed, RigidBodyDynamics::JointTypeHelical, RigidBodyDynamics::JointTypePrismatic, RigidBodyDynamics::JointTypeRevolute, RigidBodyDynamics::JointTypeRevoluteX, RigidBodyDynamics::JointTypeRevoluteY, RigidBodyDynamics::JointTypeRevoluteZ, RigidBodyDynamics::JointTypeSpherical, RigidBodyDynamics::JointTypeTranslationXYZ, RigidBodyDynamics::JointTypeUndefined, Body::mCenterOfMass, Joint::mDoFCount, Body::mInertia, Joint::mJointAxes, Joint::mJointType, and Body::mMass.
unsigned int AddBodyCustomJoint | ( | const unsigned int | parent_id, |
const Math::SpatialTransform & | joint_frame, | ||
CustomJoint * | custom_joint, | ||
const Body & | body, | ||
std::string | body_name = "" |
||
) |
Definition at line 473 of file Model.cc.
References Joint::custom_joint_index, RigidBodyDynamics::JointTypeCustom, and CustomJoint::mDoFCount.
unsigned int AddBodySphericalJoint | ( | const unsigned int | parent_id, |
const Math::SpatialTransform & | joint_frame, | ||
const Joint & | joint, | ||
const Body & | body, | ||
std::string | body_name = "" |
||
) |
unsigned int AppendBody | ( | const Math::SpatialTransform & | joint_frame, |
const Joint & | joint, | ||
const Body & | body, | ||
std::string | body_name = "" |
||
) |
Adds a Body to the model such that the previously added Body is the Parent.
This function is basically the same as Model::AddBody() however the most recently added body (or body 0) is taken as parent.
Definition at line 460 of file Model.cc.
References Model::AddBody().
|
inline |
Returns the id of a body that was passed to AddBody()
Bodies can be given a human readable name. This function allows to resolve its name to the numeric id.
std::numeric_limits<unsigned
int>::max() if the id was not found.
|
inline |
|
inline |
Returns the joint frame transformtion, i.e. the second argument to Model::AddBody().
|
inline |
|
inline |
Gets the quaternion for body i (only valid if body i is connected by a JointTypeSpherical joint)
See Joint Singularities for details.
Definition at line 460 of file Model.h.
References RigidBodyDynamics::JointTypeSpherical.
|
inline |
|
inline |
Sets the joint frame transformtion, i.e. the second argument to Model::AddBody().
|
inline |
Sets the quaternion for body i (only valid if body i is connected by a JointTypeSpherical joint)
See Joint Singularities for details.
Definition at line 475 of file Model.h.
References RigidBodyDynamics::JointTypeSpherical.
std::vector<Math::SpatialVector> a |
std::vector<Math::SpatialVector> c |
std::vector<Math::SpatialVector> c_J |
unsigned int dof_count |
std::vector<Math::SpatialVector> f |
Internal forces on the body (used only InverseDynamics())
unsigned int fixed_body_discriminator |
Value that is used to discriminate between fixed and movable bodies.
Bodies with id 1 .. (fixed_body_discriminator - 1) are moving bodies while bodies with id fixed_body_discriminator .. max (unsigned int) are fixed to a moving body. The value of max(unsigned int) is determined via std::numeric_limits<unsigned int>::max() and the default value of fixed_body_discriminator is max (unsigned int) / 2.
On normal systems max (unsigned int) is 4294967294 which means there could be a total of 2147483646 movable and / or fixed bodies.
Math::Vector3d gravity |
std::vector<Math::SpatialVector> hc |
std::vector<Math::SpatialVector> hdotc |
std::vector<Math::SpatialRigidBodyInertia> I |
The spatial inertia of body i (used only in CompositeRigidBodyAlgorithm())
std::vector<Math::SpatialMatrix> IA |
std::vector<Math::SpatialRigidBodyInertia> Ic |
std::vector<unsigned int> lambda |
std::vector<unsigned int> lambda_q |
std::vector<Body> mBodies |
std::map<std::string, unsigned int> mBodyNameMap |
std::vector<CustomJoint*> mCustomJoints |
std::vector<FixedBody> mFixedBodies |
std::vector<unsigned int> mFixedJointCount |
std::vector<std::vector<unsigned int> > mu |
std::vector<Math::Matrix3d> multdof3_Dinv |
std::vector<Math::Matrix63> multdof3_S |
std::vector<Math::Matrix63> multdof3_U |
std::vector<Math::Vector3d> multdof3_u |
std::vector<Math::SpatialVector> pA |
unsigned int previously_added_body_id |
Id of the previously added body, required for Model::AppendBody()
unsigned int q_size |
The size of the -vector. For models without spherical joints the value is the same as Model::dof_count, otherwise additional values for the w-component of the Quaternion is stored at the end of
.
unsigned int qdot_size |
std::vector<Math::SpatialVector> S |
std::vector<Math::SpatialVector> U |
std::vector<Math::SpatialVector> v |
std::vector<Math::SpatialVector> v_J |
std::vector<Math::SpatialTransform> X_base |
std::vector<Math::SpatialTransform> X_lambda |
std::vector<Math::SpatialTransform> X_T |