Robot Dynamics Library
|
Contains all information about the rigid body model. More...
#include <Model.hpp>
Public Types | |
using | SharedPtr = std::shared_ptr< Model > |
Public Member Functions | |
Model (const rclcpp::Node::SharedPtr &n=nullptr, unsigned int *n_threads=nullptr) | |
Constructor. More... | |
~Model () | |
Model (const Model &)=delete | |
void | operator= (const Model &)=delete |
void | setupRosParameters () |
Call this after the model is fully populated to declare ros parameters that define the mass parameters for each body. This allows them to be modified at runtime. More... | |
rcl_interfaces::msg::SetParametersResult | paramCb (const std::vector< rclcpp::Parameter > ¶meters) |
bool | setThreadParameters (int policy, struct sched_param param) |
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... | |
ReferenceFramePtr | getReferenceFrame (const std::string &frameName) const |
Get a fixed or moveable body's reference frame. 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) const |
Checks whether the body is rigidly attached to another body. More... | |
bool | IsBodyId (unsigned int id) const |
unsigned int | GetParentBodyId (unsigned int id) |
Determines id the actual parent body. More... | |
Math::SpatialTransform | GetJointFrame (unsigned int id) |
Returns the joint frame transformtion, i.e. the second argument to Model::addBody(). More... | |
void | SetJointFrame (unsigned int id, const Math::SpatialTransform &transform) |
Sets the joint frame transformtion, i.e. the second argument to Model::addBody(). More... | |
Math::Quaternion | GetQuaternion (unsigned int i, const Math::VectorNd &Q) const |
Gets the quaternion for body i (only valid if body i is connected by a JointTypeSpherical joint) More... | |
void | SetQuaternion (unsigned int i, const Math::Quaternion &quat, Math::VectorNd &Q) const |
Sets the quaternion for body i (only valid if body i is connected by a JointTypeSpherical joint) More... | |
unsigned int | getCommonMovableParentId (unsigned int id_1, unsigned int id_2) const |
void | crawlChainKinematics (unsigned int b_id, std::atomic< unsigned int > *branch_ends, const Math::VectorNd *Q, const Math::VectorNd *QDot, const Math::VectorNd *QDDot) |
Public Attributes | |
ReferenceFramePtr | worldFrame |
std::vector< ReferenceFramePtr > | bodyFrames |
std::vector< ReferenceFramePtr > | bodyCenteredFrames |
std::vector< ReferenceFramePtr > | bodyCenterOfBuoyancyFrames |
std::vector< ReferenceFramePtr > | fixedBodyFrames |
std::vector< unsigned int > | lambda |
std::vector< std::vector< unsigned int > > | lambda_chain |
std::vector< unsigned int > | lambda_q |
std::vector< std::vector< unsigned int > > | mu |
unsigned int | dof_count = 0 |
number of degrees of freedoms of the model More... | |
unsigned int | q_size = 0 |
The size of the ![]() ![]() | |
unsigned int | qdot_size = 0 |
The size of the. More... | |
double | mass = 0. |
double | volume = 0. |
unsigned int | previously_added_body_id = 0 |
Id of the previously added body, required for Model::appendBody() More... | |
Math::MotionVector | gravity |
the cartesian vector of the gravity More... | |
double | fluidDensity = 1000. |
Math::MotionVector | a_f |
Math::MotionVector | v_f |
Math::SpatialAccelerationV | a |
The spatial velocity of the bodies. More... | |
Math::SpatialMotionV | v |
std::vector< Joint > | mJoints |
All joints. More... | |
Math::MotionVectorV | S |
Math::MotionVectorV | S_o |
std::vector< Math::SpatialTransform > | X_J |
std::vector< Math::SpatialVector > | c_J |
Math::SpatialMotionV | v_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_S_o |
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... | |
Math::SpatialForceV | 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... | |
Math::SpatialForceV | f |
Internal forces on the body (used only InverseDynamics()) More... | |
Math::SpatialForceV | f_b |
Math::SpatialInertiaV | I |
Math::RigidBodyInertiaV | Ic |
std::vector< Math::SpatialMatrix > | I_add |
std::vector< Math::SpatialMatrix > | I_H |
std::vector< Math::SpatialMatrix > | Ic_H |
Math::SpatialInertiaV | Ib_c |
std::vector< Math::Momentum > | hc |
Math::MatrixNd | ndof0_mat |
Math::MatrixNd | three_x_qd0 |
Math::VectorNd | q0_vec |
Math::VectorNd | ndof0_vec |
Math::VectorNd | nbodies0_vec |
std::vector< Math::SpatialTransform > | X_lambda |
Transformation from the parent body to the current body. More... | |
std::vector< FixedBody > | mFixedBodies |
All bodies that are attached to a body via a fixed joint. More... | |
unsigned int | fixed_body_discriminator = std::numeric_limits<unsigned int>::max() / 2 |
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... | |
std::map< std::string, ReferenceFramePtr > | referenceFrameMap |
unsigned int | num_branch_ends = 0 |
ReferenceFramePtr | comFrame |
ReferenceFramePtr | cobFrame |
boost::asio::io_service | io_service |
std::unique_ptr< boost::asio::io_service::work > | work |
std::vector< boost::thread * > | threads |
boost::thread_group | thread_pool |
rclcpp::Node::SharedPtr | node |
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr | callback_handle |
Private Member Functions | |
bool | validateRigidBodyInertia (const Body &body) |
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.
using RobotDynamics::Model::SharedPtr = std::shared_ptr<Model> |
|
explicit |
Constructor.
n_threads | The number of threads that the model can create for performing parallel tasks such as parallel kinematics. This defaults to nullptr in which case the number of threads created will be equal to std::thread::hardware_concurrency() |
Initialize fluid velocity/accel to zero
|
inline |
|
delete |
unsigned int Model::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()) |
Hydrodynamics
Added mass matrix I_add contains the added mass matrix plus the bodies rigid body inertia matrix
unsigned int Model::addBodyCustomJoint | ( | const unsigned int | parent_id, |
const Math::SpatialTransform & | joint_frame, | ||
CustomJoint * | custom_joint, | ||
const Body & | body, | ||
std::string | body_name = "" |
||
) |
unsigned int RobotDynamics::Model::addBodySphericalJoint | ( | const unsigned int | parent_id, |
const Math::SpatialTransform & | joint_frame, | ||
const Joint & | joint, | ||
const Body & | body, | ||
std::string | body_name = "" |
||
) |
unsigned int Model::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.
void Model::crawlChainKinematics | ( | unsigned int | b_id, |
std::atomic< unsigned int > * | branch_ends, | ||
const Math::VectorNd * | Q, | ||
const Math::VectorNd * | QDot, | ||
const Math::VectorNd * | QDDot | ||
) |
|
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.
|
inline |
Returns the name of a body for a given body id.
|
inline |
|
inline |
Returns the joint frame transformtion, i.e. the second argument to Model::addBody().
|
inline |
Determines id the actual parent body.
|
inline |
Gets the quaternion for body i (only valid if body i is connected by a JointTypeSpherical joint)
See Joint Singularities for details.
|
inline |
Get a fixed or moveable body's reference frame.
|
inline |
|
inline |
Checks whether the body is rigidly attached to another body.
|
delete |
rcl_interfaces::msg::SetParametersResult Model::paramCb | ( | const std::vector< rclcpp::Parameter > & | parameters | ) |
|
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.
|
inline |
void Model::setupRosParameters | ( | ) |
Call this after the model is fully populated to declare ros parameters that define the mass parameters for each body. This allows them to be modified at runtime.
|
inlineprivate |
Math::SpatialAccelerationV RobotDynamics::Model::a |
The spatial velocity of the bodies.
The spatial acceleration of the bodies expressed in body frame
Math::MotionVector RobotDynamics::Model::a_f |
The acceleration, in base coords, of the fluid the model is immersed in
std::vector<ReferenceFramePtr> RobotDynamics::Model::bodyCenteredFrames |
< Body centered frames are aligned with the body frame, but located at a body's center of mass
std::vector<ReferenceFramePtr> RobotDynamics::Model::bodyCenterOfBuoyancyFrames |
A vector of body frames that are located at the body's center of buoyancy and aligned with the body frame
std::vector<ReferenceFramePtr> RobotDynamics::Model::bodyFrames |
Reference frames for each body. Frame names are the same as the body name
std::vector<Math::SpatialVector> RobotDynamics::Model::c |
The velocity dependent spatial acceleration.
std::vector<Math::SpatialVector> RobotDynamics::Model::c_J |
Apparent derivative of v_J in a coordinate moving with the successor body
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr RobotDynamics::Model::callback_handle |
ReferenceFramePtr RobotDynamics::Model::cobFrame |
ReferenceFramePtr RobotDynamics::Model::comFrame |
Reference frame who's origin is located at the robots center of buoyancy
Math::VectorNd RobotDynamics::Model::d |
Temporary variable D_i (RBDA p. 130)
unsigned int RobotDynamics::Model::dof_count = 0 |
number of degrees of freedoms of the model
This value contains the number of entries in the generalized state (q) velocity (qdot), acceleration (qddot), and force (tau) vector.
Math::SpatialForceV RobotDynamics::Model::f |
Internal forces on the body (used only InverseDynamics())
Math::SpatialForceV RobotDynamics::Model::f_b |
unsigned int RobotDynamics::Model::fixed_body_discriminator = std::numeric_limits<unsigned int>::max() / 2 |
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.
std::vector<ReferenceFramePtr> RobotDynamics::Model::fixedBodyFrames |
double RobotDynamics::Model::fluidDensity = 1000. |
The density( ) of the surrounding fluid
Math::MotionVector RobotDynamics::Model::gravity |
the cartesian vector of the gravity
std::vector<Math::Momentum> RobotDynamics::Model::hc |
Math::SpatialInertiaV RobotDynamics::Model::I |
Body inertia expressed in body frame
std::vector<Math::SpatialMatrix> RobotDynamics::Model::I_add |
Added inertia matrix for each body
std::vector<Math::SpatialMatrix> RobotDynamics::Model::I_H |
Combined body and added mass inertia
std::vector<Math::SpatialMatrix> RobotDynamics::Model::IA |
The spatial inertia of the bodies.
Math::SpatialInertiaV RobotDynamics::Model::Ib_c |
Ib_c is the inertia of (non-fixed) bodies expressed in the body's center of mass frame.
Math::RigidBodyInertiaV RobotDynamics::Model::Ic |
A body inertia. See RobotDynamics::compositeRigidBodyAlgorithm for the uses of this
std::vector<Math::SpatialMatrix> RobotDynamics::Model::Ic_H |
Used only in the hydrodynamics implementation of compositeRigidBodyAlgorithm
boost::asio::io_service RobotDynamics::Model::io_service |
std::vector<unsigned int> RobotDynamics::Model::lambda |
The id of the parents body
std::vector<std::vector<unsigned int> > RobotDynamics::Model::lambda_chain |
Each body's chain of parents
std::vector<unsigned int> RobotDynamics::Model::lambda_q |
The index of the parent degree of freedom that is directly influencing the current one
double RobotDynamics::Model::mass = 0. |
total robot volume(m^3)
std::vector<Body> RobotDynamics::Model::mBodies |
All bodies 0 ... N_B, including the base.
mBodies[0] - base body
mBodies[1] - 1st moveable body
...
mBodies[N_B] - N_Bth moveable body
std::map<std::string, unsigned int> RobotDynamics::Model::mBodyNameMap |
Human readable names for the bodies.
Map containaing name -> pointer to reference frame for each frame on the robot
std::vector<CustomJoint*> RobotDynamics::Model::mCustomJoints |
std::vector<FixedBody> RobotDynamics::Model::mFixedBodies |
All bodies that are attached to a body via a fixed joint.
std::vector<unsigned int> RobotDynamics::Model::mFixedJointCount |
The number of fixed joints that have been declared before each joint.
std::vector<Joint> RobotDynamics::Model::mJoints |
All joints.
std::vector<unsigned int> RobotDynamics::Model::mJointUpdateOrder |
std::vector<std::vector<unsigned int> > RobotDynamics::Model::mu |
Contains the ids of all the children of a given body
std::vector<Math::Matrix3d> RobotDynamics::Model::multdof3_Dinv |
std::vector<Math::Matrix63> RobotDynamics::Model::multdof3_S |
Motion subspace for joints with 3 degrees of freedom.
std::vector<Math::Matrix63> RobotDynamics::Model::multdof3_S_o |
std::vector<Math::Matrix63> RobotDynamics::Model::multdof3_U |
std::vector<Math::Vector3d> RobotDynamics::Model::multdof3_u |
std::vector<unsigned int> RobotDynamics::Model::multdof3_w_index |
Math::VectorNd RobotDynamics::Model::nbodies0_vec |
mBodies.size() x 1 vector of zeros
Math::MatrixNd RobotDynamics::Model::ndof0_mat |
Math::VectorNd RobotDynamics::Model::ndof0_vec |
ndof x 1 vector of zeros
rclcpp::Node::SharedPtr RobotDynamics::Model::node |
unsigned int RobotDynamics::Model::num_branch_ends = 0 |
Reference frame who's origin is located at the robots center of mass, aligned with world frame
Math::SpatialForceV RobotDynamics::Model::pA |
The spatial bias force.
unsigned int RobotDynamics::Model::previously_added_body_id = 0 |
Id of the previously added body, required for Model::appendBody()
Math::VectorNd RobotDynamics::Model::q0_vec |
q_size x 1 vector of zeros
unsigned int RobotDynamics::Model::q_size = 0 |
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 RobotDynamics::Model::qdot_size = 0 |
std::map<std::string, ReferenceFramePtr> RobotDynamics::Model::referenceFrameMap |
Math::MotionVectorV RobotDynamics::Model::S |
Motion subspace for 1 dof joints
Math::MotionVectorV RobotDynamics::Model::S_o |
The ring derivative of S, a.k.a the rate of growth
boost::thread_group RobotDynamics::Model::thread_pool |
std::vector<boost::thread*> RobotDynamics::Model::threads |
Math::MatrixNd RobotDynamics::Model::three_x_qd0 |
3 x qdot_size matrix of zeros
std::vector<Math::SpatialVector> RobotDynamics::Model::U |
Temporary variable U_i (RBDA p. 130)
Math::VectorNd RobotDynamics::Model::u |
Temporary variable u (RBDA p. 130)
Math::SpatialMotionV RobotDynamics::Model::v |
The spatial velocity of the bodies expressed in body frame
Math::MotionVector RobotDynamics::Model::v_f |
The velocity, in base coords, of the fluid the model is immersed in
Math::SpatialMotionV RobotDynamics::Model::v_J |
Joints velocity w.r.t its parent joint, expressed in body frame
double RobotDynamics::Model::volume = 0. |
std::unique_ptr<boost::asio::io_service::work> RobotDynamics::Model::work |
ReferenceFramePtr RobotDynamics::Model::worldFrame |
Pointer to world frame
std::vector<Math::SpatialTransform> RobotDynamics::Model::X_J |
std::vector<Math::SpatialTransform> RobotDynamics::Model::X_lambda |
Transformation from the parent body to the current body.
std::vector<Math::SpatialTransform> RobotDynamics::Model::X_T |
Transformations from the parent body to the frame of the joint.