Robot Dynamics Library
Public Types | Public Member Functions | Public Attributes | Private Member Functions | List of all members
RobotDynamics::Model Struct Reference

Contains all information about the rigid body model. More...

#include <Model.hpp>

Collaboration diagram for RobotDynamics::Model:
Collaboration graph
[legend]

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 > &parameters)
 
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< ReferenceFramePtrbodyFrames
 
std::vector< ReferenceFramePtrbodyCenteredFrames
 
std::vector< ReferenceFramePtrbodyCenterOfBuoyancyFrames
 
std::vector< ReferenceFramePtrfixedBodyFrames
 
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 $\mathbf{q}$-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 $\mathbf{q}$. More...
 
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< JointmJoints
 All joints. More...
 
Math::MotionVectorV S
 
Math::MotionVectorV S_o
 
std::vector< Math::SpatialTransformX_J
 
std::vector< Math::SpatialVectorc_J
 
Math::SpatialMotionV v_J
 
std::vector< unsigned int > mJointUpdateOrder
 
std::vector< Math::SpatialTransformX_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::Matrix63multdof3_S
 Motion subspace for joints with 3 degrees of freedom. More...
 
std::vector< Math::Matrix63multdof3_S_o
 
std::vector< Math::Matrix63multdof3_U
 
std::vector< Math::Matrix3dmultdof3_Dinv
 
std::vector< Math::Vector3dmultdof3_u
 
std::vector< unsigned int > multdof3_w_index
 
std::vector< CustomJoint * > mCustomJoints
 
std::vector< Math::SpatialVectorc
 The velocity dependent spatial acceleration. More...
 
std::vector< Math::SpatialMatrixIA
 The spatial inertia of the bodies. More...
 
Math::SpatialForceV pA
 The spatial bias force. More...
 
std::vector< Math::SpatialVectorU
 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::SpatialMatrixI_add
 
std::vector< Math::SpatialMatrixI_H
 
std::vector< Math::SpatialMatrixIc_H
 
Math::SpatialInertiaV Ib_c
 
std::vector< Math::Momentumhc
 
Math::MatrixNd ndof0_mat
 
Math::MatrixNd three_x_qd0
 
Math::VectorNd q0_vec
 
Math::VectorNd ndof0_vec
 
Math::VectorNd nbodies0_vec
 
std::vector< Math::SpatialTransformX_lambda
 Transformation from the parent body to the current body. More...
 
std::vector< FixedBodymFixedBodies
 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< BodymBodies
 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, ReferenceFramePtrreferenceFrameMap
 
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)
 

Detailed Description

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.

Todo:
  • Need to implement proper copy constructor, so I can use raw pointers and can clean them up properly
Note
To query the number of degrees of freedom use Model::dof_count.

Member Typedef Documentation

◆ SharedPtr

using RobotDynamics::Model::SharedPtr = std::shared_ptr<Model>

Constructor & Destructor Documentation

◆ Model() [1/2]

Model::Model ( const rclcpp::Node::SharedPtr &  n = nullptr,
unsigned int *  n_threads = nullptr 
)
explicit

Constructor.

Parameters
n_threadsThe 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

◆ ~Model()

RobotDynamics::Model::~Model ( )
inline

◆ Model() [2/2]

RobotDynamics::Model::Model ( const Model )
delete

Member Function Documentation

◆ addBody()

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:

  • what kind of body will be added?
  • where is the new body to be added?
  • by what kind of joint should the body be added?

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.

Parameters
parent_idid of the parent body
joint_framethe transformation from the parent frame to the origin of the joint frame (represents X_T in RBDA)
jointspecification for the joint that describes the connection
bodyspecification of the body itself
body_namehuman readable name for the body (can be used to retrieve its id with GetBodyId())
Returns
id of the added body

Hydrodynamics

Added mass matrix I_add contains the added mass matrix plus the bodies rigid body inertia matrix

◆ addBodyCustomJoint()

unsigned int Model::addBodyCustomJoint ( const unsigned int  parent_id,
const Math::SpatialTransform joint_frame,
CustomJoint custom_joint,
const Body body,
std::string  body_name = "" 
)

◆ addBodySphericalJoint()

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 = "" 
)

◆ appendBody()

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.

◆ crawlChainKinematics()

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 
)

◆ GetBodyId()

unsigned int RobotDynamics::Model::GetBodyId ( const char *  body_name) const
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.

Note
Instead of querying this function repeatedly, it might be advisable to query it once and reuse the returned id.
Returns
the id of the body or
std::numeric_limits<unsigned int>::max()
if the id was not found.

◆ GetBodyName()

std::string RobotDynamics::Model::GetBodyName ( unsigned int  body_id) const
inline

Returns the name of a body for a given body id.

◆ getCommonMovableParentId()

unsigned int RobotDynamics::Model::getCommonMovableParentId ( unsigned int  id_1,
unsigned int  id_2 
) const
inline

◆ GetJointFrame()

Math::SpatialTransform RobotDynamics::Model::GetJointFrame ( unsigned int  id)
inline

Returns the joint frame transformtion, i.e. the second argument to Model::addBody().

◆ GetParentBodyId()

unsigned int RobotDynamics::Model::GetParentBodyId ( unsigned int  id)
inline

Determines id the actual parent body.

Note
When adding bodies using joints with multiple degrees of freedom, additional virtual bodies are added for each degree of freedom. This function returns the id of the actual non-virtual parent body.

◆ GetQuaternion()

Math::Quaternion RobotDynamics::Model::GetQuaternion ( unsigned int  i,
const Math::VectorNd Q 
) const
inline

Gets the quaternion for body i (only valid if body i is connected by a JointTypeSpherical joint)

See Joint Singularities for details.

◆ getReferenceFrame()

ReferenceFramePtr RobotDynamics::Model::getReferenceFrame ( const std::string &  frameName) const
inline

Get a fixed or moveable body's reference frame.

Returns
Pointer to the frame, or nullptr if it doesn't exist

◆ IsBodyId()

bool RobotDynamics::Model::IsBodyId ( unsigned int  id) const
inline

◆ IsFixedBodyId()

bool RobotDynamics::Model::IsFixedBodyId ( unsigned int  body_id) const
inline

Checks whether the body is rigidly attached to another body.

◆ operator=()

void RobotDynamics::Model::operator= ( const Model )
delete

◆ paramCb()

rcl_interfaces::msg::SetParametersResult Model::paramCb ( const std::vector< rclcpp::Parameter > &  parameters)

◆ SetJointFrame()

void RobotDynamics::Model::SetJointFrame ( unsigned int  id,
const Math::SpatialTransform transform 
)
inline

Sets the joint frame transformtion, i.e. the second argument to Model::addBody().

◆ SetQuaternion()

void RobotDynamics::Model::SetQuaternion ( unsigned int  i,
const Math::Quaternion quat,
Math::VectorNd Q 
) const
inline

Sets the quaternion for body i (only valid if body i is connected by a JointTypeSpherical joint)

See Joint Singularities for details.

◆ setThreadParameters()

bool RobotDynamics::Model::setThreadParameters ( int  policy,
struct sched_param  param 
)
inline

◆ setupRosParameters()

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.

Note
If the node provided to the model at runtime is nullptr this function immediately returns

◆ validateRigidBodyInertia()

bool RobotDynamics::Model::validateRigidBodyInertia ( const Body body)
inlineprivate

Member Data Documentation

◆ a

Math::SpatialAccelerationV RobotDynamics::Model::a

The spatial velocity of the bodies.

The spatial acceleration of the bodies expressed in body frame

◆ a_f

Math::MotionVector RobotDynamics::Model::a_f

The acceleration, in base coords, of the fluid the model is immersed in

◆ bodyCenteredFrames

std::vector<ReferenceFramePtr> RobotDynamics::Model::bodyCenteredFrames

< Body centered frames are aligned with the body frame, but located at a body's center of mass

◆ bodyCenterOfBuoyancyFrames

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

◆ bodyFrames

std::vector<ReferenceFramePtr> RobotDynamics::Model::bodyFrames

Reference frames for each body. Frame names are the same as the body name

◆ c

std::vector<Math::SpatialVector> RobotDynamics::Model::c

The velocity dependent spatial acceleration.

◆ c_J

std::vector<Math::SpatialVector> RobotDynamics::Model::c_J

Apparent derivative of v_J in a coordinate moving with the successor body

◆ callback_handle

rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr RobotDynamics::Model::callback_handle

◆ cobFrame

ReferenceFramePtr RobotDynamics::Model::cobFrame

◆ comFrame

ReferenceFramePtr RobotDynamics::Model::comFrame

Reference frame who's origin is located at the robots center of buoyancy

◆ d

Math::VectorNd RobotDynamics::Model::d

Temporary variable D_i (RBDA p. 130)

◆ dof_count

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.

◆ f

Math::SpatialForceV RobotDynamics::Model::f

Internal forces on the body (used only InverseDynamics())

◆ f_b

Math::SpatialForceV RobotDynamics::Model::f_b

◆ fixed_body_discriminator

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.

◆ fixedBodyFrames

std::vector<ReferenceFramePtr> RobotDynamics::Model::fixedBodyFrames

◆ fluidDensity

double RobotDynamics::Model::fluidDensity = 1000.

The density( $ \frac{kg}{m^3} $) of the surrounding fluid

◆ gravity

Math::MotionVector RobotDynamics::Model::gravity

the cartesian vector of the gravity

◆ hc

std::vector<Math::Momentum> RobotDynamics::Model::hc

◆ I

Math::SpatialInertiaV RobotDynamics::Model::I

Body inertia expressed in body frame

◆ I_add

std::vector<Math::SpatialMatrix> RobotDynamics::Model::I_add

Added inertia matrix for each body

◆ I_H

std::vector<Math::SpatialMatrix> RobotDynamics::Model::I_H

Combined body and added mass inertia

◆ IA

std::vector<Math::SpatialMatrix> RobotDynamics::Model::IA

The spatial inertia of the bodies.

◆ Ib_c

Math::SpatialInertiaV RobotDynamics::Model::Ib_c

Ib_c is the inertia of (non-fixed) bodies expressed in the body's center of mass frame.

◆ Ic

Math::RigidBodyInertiaV RobotDynamics::Model::Ic

A body inertia. See RobotDynamics::compositeRigidBodyAlgorithm for the uses of this

◆ Ic_H

std::vector<Math::SpatialMatrix> RobotDynamics::Model::Ic_H

Used only in the hydrodynamics implementation of compositeRigidBodyAlgorithm

◆ io_service

boost::asio::io_service RobotDynamics::Model::io_service

◆ lambda

std::vector<unsigned int> RobotDynamics::Model::lambda

The id of the parents body

◆ lambda_chain

std::vector<std::vector<unsigned int> > RobotDynamics::Model::lambda_chain

Each body's chain of parents

◆ lambda_q

std::vector<unsigned int> RobotDynamics::Model::lambda_q

The index of the parent degree of freedom that is directly influencing the current one

◆ mass

double RobotDynamics::Model::mass = 0.

total robot volume(m^3)

◆ mBodies

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

◆ mBodyNameMap

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

◆ mCustomJoints

std::vector<CustomJoint*> RobotDynamics::Model::mCustomJoints

◆ mFixedBodies

std::vector<FixedBody> RobotDynamics::Model::mFixedBodies

All bodies that are attached to a body via a fixed joint.

◆ mFixedJointCount

std::vector<unsigned int> RobotDynamics::Model::mFixedJointCount

The number of fixed joints that have been declared before each joint.

◆ mJoints

std::vector<Joint> RobotDynamics::Model::mJoints

All joints.

◆ mJointUpdateOrder

std::vector<unsigned int> RobotDynamics::Model::mJointUpdateOrder

◆ mu

std::vector<std::vector<unsigned int> > RobotDynamics::Model::mu

Contains the ids of all the children of a given body

◆ multdof3_Dinv

std::vector<Math::Matrix3d> RobotDynamics::Model::multdof3_Dinv

◆ multdof3_S

std::vector<Math::Matrix63> RobotDynamics::Model::multdof3_S

Motion subspace for joints with 3 degrees of freedom.

◆ multdof3_S_o

std::vector<Math::Matrix63> RobotDynamics::Model::multdof3_S_o

◆ multdof3_U

std::vector<Math::Matrix63> RobotDynamics::Model::multdof3_U

◆ multdof3_u

std::vector<Math::Vector3d> RobotDynamics::Model::multdof3_u

◆ multdof3_w_index

std::vector<unsigned int> RobotDynamics::Model::multdof3_w_index

◆ nbodies0_vec

Math::VectorNd RobotDynamics::Model::nbodies0_vec

mBodies.size() x 1 vector of zeros

◆ ndof0_mat

Math::MatrixNd RobotDynamics::Model::ndof0_mat
Note
It's CRITICAL that the elements of the zero matrices never be modified! It will break absolutely everything. ndof x ndof matrix of zeros

◆ ndof0_vec

Math::VectorNd RobotDynamics::Model::ndof0_vec

ndof x 1 vector of zeros

◆ node

rclcpp::Node::SharedPtr RobotDynamics::Model::node

◆ num_branch_ends

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

◆ pA

Math::SpatialForceV RobotDynamics::Model::pA

The spatial bias force.

◆ previously_added_body_id

unsigned int RobotDynamics::Model::previously_added_body_id = 0

Id of the previously added body, required for Model::appendBody()

◆ q0_vec

Math::VectorNd RobotDynamics::Model::q0_vec

q_size x 1 vector of zeros

◆ q_size

unsigned int RobotDynamics::Model::q_size = 0

The size of the $\mathbf{q}$-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 $\mathbf{q}$.

See also
Joint Modeling for more details.

◆ qdot_size

unsigned int RobotDynamics::Model::qdot_size = 0

The size of the.

( $\mathbf{\dot{q}}, \mathbf{\ddot{q}}$, and $\mathbf{\tau}$-vector.

See also
Joint Modeling for more details. total robot mass(kg)

◆ referenceFrameMap

std::map<std::string, ReferenceFramePtr> RobotDynamics::Model::referenceFrameMap

◆ S

Math::MotionVectorV RobotDynamics::Model::S

Motion subspace for 1 dof joints

◆ S_o

Math::MotionVectorV RobotDynamics::Model::S_o

The ring derivative of S, a.k.a the rate of growth

◆ thread_pool

boost::thread_group RobotDynamics::Model::thread_pool

◆ threads

std::vector<boost::thread*> RobotDynamics::Model::threads

◆ three_x_qd0

Math::MatrixNd RobotDynamics::Model::three_x_qd0

3 x qdot_size matrix of zeros

◆ U

std::vector<Math::SpatialVector> RobotDynamics::Model::U

Temporary variable U_i (RBDA p. 130)

◆ u

Math::VectorNd RobotDynamics::Model::u

Temporary variable u (RBDA p. 130)

◆ v

Math::SpatialMotionV RobotDynamics::Model::v

The spatial velocity of the bodies expressed in body frame

◆ v_f

Math::MotionVector RobotDynamics::Model::v_f

The velocity, in base coords, of the fluid the model is immersed in

◆ v_J

Math::SpatialMotionV RobotDynamics::Model::v_J

Joints velocity w.r.t its parent joint, expressed in body frame

◆ volume

double RobotDynamics::Model::volume = 0.

◆ work

std::unique_ptr<boost::asio::io_service::work> RobotDynamics::Model::work

◆ worldFrame

ReferenceFramePtr RobotDynamics::Model::worldFrame

Pointer to world frame

◆ X_J

std::vector<Math::SpatialTransform> RobotDynamics::Model::X_J

◆ X_lambda

std::vector<Math::SpatialTransform> RobotDynamics::Model::X_lambda

Transformation from the parent body to the current body.

\[ X_{\lambda(i)} = {}^{i} X_{\lambda(i)} \]

◆ X_T

std::vector<Math::SpatialTransform> RobotDynamics::Model::X_T

Transformations from the parent body to the frame of the joint.


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