Biorbd
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
biorbd::rigidbody::Joints Class Reference

This is the core of the musculoskeletal model in biorbd. More...

#include <Joints.h>

Inheritance diagram for biorbd::rigidbody::Joints:
biorbd::Model

Public Member Functions

 Joints ()
 Construct a joint model.
 
 Joints (const biorbd::rigidbody::Joints &other)
 Construct a joint model from another model. More...
 
virtual ~Joints ()
 Properly destroy class.
 
biorbd::rigidbody::Joints DeepCopy () const
 Deep copy of the joints. More...
 
void DeepCopy (const biorbd::rigidbody::Joints &other)
 Deep copy of the joints. More...
 
unsigned int AddSegment (const biorbd::utils::String &segmentName, const biorbd::utils::String &parentName, const biorbd::utils::String &translationSequence, const biorbd::utils::String &rotationSequence, const std::vector< biorbd::utils::Range > &QRanges, const std::vector< biorbd::utils::Range > &QDotRanges, const std::vector< biorbd::utils::Range > &QDDotRanges, const biorbd::rigidbody::SegmentCharacteristics &characteristics, const RigidBodyDynamics::Math::SpatialTransform &centreOfRotation, int forcePlates=-1)
 Add a segment to the model. More...
 
unsigned int AddSegment (const biorbd::utils::String &segmentName, const biorbd::utils::String &parentName, const biorbd::utils::String &translationSequence, const std::vector< biorbd::utils::Range > &QRanges, const std::vector< biorbd::utils::Range > &QDotRanges, const std::vector< biorbd::utils::Range > &QDDotRanges, const biorbd::rigidbody::SegmentCharacteristics &characteristics, const RigidBodyDynamics::Math::SpatialTransform &centreOfRotation, int forcePlates=-1)
 Add a segment to the model. More...
 
biorbd::utils::Vector3d getGravity () const
 Get the current gravity. More...
 
void setGravity (const biorbd::utils::Vector3d &newGravity)
 Set the gravity. More...
 
int GetBodyBiorbdId (const biorbd::utils::String &segmentName) const
 Return the biorbd body identification. More...
 
unsigned int nbGeneralizedTorque () const
 Return the number of generalized torque. More...
 
unsigned int nbSegment () const
 Return the actual number of segment. More...
 
unsigned int nbDof () const
 Return the number of degrees of freedom (DoF) More...
 
unsigned int getDofIndex (const biorbd::utils::String &SegmentName, const biorbd::utils::String &dofName)
 Return the index of a DoF in a segment. More...
 
std::vector< biorbd::utils::StringnameDof () const
 Return the names of the degree of freedom (DoF) More...
 
unsigned int nbQ () const
 Return the number of generalized coordinates (Q) More...
 
unsigned int nbQdot () const
 Return the number of generalized velocities (Qdot) More...
 
unsigned int nbQddot () const
 Return the number of generalized acceleration (Qddot) More...
 
unsigned int nbRoot () const
 Return the dof on the root. More...
 
unsigned int nbQuat () const
 Return the number of segments that are described using quaternions. More...
 
const biorbd::rigidbody::Segmentsegment (unsigned int idx) const
 Get a segment of index idx. More...
 
const biorbd::rigidbody::Segmentsegment (const biorbd::utils::String &name) const
 Get a segment of a specific name. More...
 
std::vector< RigidBodyDynamics::Math::SpatialVector > dispatchedForce (std::vector< std::vector< biorbd::utils::SpatialVector >> &spatialVector, unsigned int frame) const
 Dispatch the forces from the force plate in a vector. More...
 
std::vector< RigidBodyDynamics::Math::SpatialVector > dispatchedForce (std::vector< biorbd::utils::SpatialVector > &sv) const
 Dispatch the forces from the force plate in a spatial vector. More...
 
void UpdateKinematicsCustom (const biorbd::rigidbody::GeneralizedCoordinates *Q=nullptr, const biorbd::rigidbody::GeneralizedVelocity *Qdot=nullptr, const biorbd::rigidbody::GeneralizedAcceleration *Qddot=nullptr)
 Update the kinematic variables such as body velocities and accelerations in the model to reflect the variables passed to this function. More...
 
std::vector< biorbd::utils::RotoTransallGlobalJCS (const biorbd::rigidbody::GeneralizedCoordinates &Q)
 Return the joint coordinate system (JCS) in global reference frame at a given Q. More...
 
std::vector< biorbd::utils::RotoTransallGlobalJCS () const
 Return the joint coordinate system (JCS) in global reference frame at a given Q. More...
 
biorbd::utils::RotoTrans globalJCS (const biorbd::rigidbody::GeneralizedCoordinates &Q, const biorbd::utils::String &name)
 Return the joint coordinate system (JCS) for the segment in global reference frame at a given Q. More...
 
biorbd::utils::RotoTrans globalJCS (const biorbd::rigidbody::GeneralizedCoordinates &Q, unsigned int idx)
 Return the joint coordinate system (JCS) for the segment idx in global reference frame at a given Q. More...
 
biorbd::utils::RotoTrans globalJCS (const biorbd::utils::String &name) const
 Return the joint coordinate system (JCS) for the segment in global reference. More...
 
biorbd::utils::RotoTrans globalJCS (unsigned int idx) const
 Return the joint coordinate system (JCS) for the segment idx in global reference. More...
 
std::vector< biorbd::utils::RotoTranslocalJCS () const
 Return all the joint coordinate system (JCS) in its parent reference frame. More...
 
biorbd::utils::RotoTrans localJCS (const biorbd::utils::String &name) const
 Return the joint coordinate system (JCS) of the segment its parent reference frame. More...
 
biorbd::utils::RotoTrans localJCS (const unsigned int idx) const
 Return the joint coordinate system (JCS) of the segment idx its parent reference frame. More...
 
biorbd::rigidbody::NodeSegment projectPoint (const biorbd::rigidbody::GeneralizedCoordinates &Q, const biorbd::utils::Vector3d &v, int segmentIdx, const biorbd::utils::String &axesToRemove, bool updateKin=true)
 Project a point on specific axis of a segment. More...
 
std::vector< biorbd::rigidbody::NodeSegmentprojectPoint (const biorbd::rigidbody::GeneralizedCoordinates &Q, const std::vector< biorbd::rigidbody::NodeSegment > &v, bool updateKin=true)
 Project multiples points on their respective segment. More...
 
biorbd::rigidbody::NodeSegment projectPoint (const biorbd::rigidbody::GeneralizedCoordinates &Q, const biorbd::rigidbody::NodeSegment &n, bool updateKin)
 Return the projected markers from a point corresponding to a marker from the model. More...
 
biorbd::utils::Matrix projectPointJacobian (const biorbd::rigidbody::GeneralizedCoordinates &Q, biorbd::rigidbody::NodeSegment p, bool updateKin)
 Return the jacobian matrix of the projected markers for a marker from the model. More...
 
biorbd::utils::Matrix projectPointJacobian (const biorbd::rigidbody::GeneralizedCoordinates &Q, const biorbd::utils::Vector3d &v, int segmentIdx, const biorbd::utils::String &axesToRemove, bool updateKin)
 Return the Jacobian matrix of a projected marker on the segment segmentIdx. More...
 
std::vector< biorbd::utils::MatrixprojectPointJacobian (const biorbd::rigidbody::GeneralizedCoordinates &Q, const std::vector< biorbd::rigidbody::NodeSegment > &v, bool updateKin)
 Return the jacobian matrix of the projected markers. More...
 
double mass () const
 Return the total mass of the model. More...
 
biorbd::utils::Vector3d CoM (const biorbd::rigidbody::GeneralizedCoordinates &Q, bool updateKin=true)
 Return the position of the center of mass. More...
 
std::vector< biorbd::rigidbody::NodeSegmentCoMbySegment (const biorbd::rigidbody::GeneralizedCoordinates &Q, bool updateKin=true)
 Return the position of the center of mass of each segment. More...
 
biorbd::utils::Matrix CoMbySegmentInMatrix (const biorbd::rigidbody::GeneralizedCoordinates &Q, bool updateKin=true)
 Return the position of the center of mass of each segment in a matrix. More...
 
biorbd::utils::Vector3d CoMbySegment (const biorbd::rigidbody::GeneralizedCoordinates &Q, const unsigned int idx, bool updateKin=true)
 Return the position of the center of mass of segment idx. More...
 
biorbd::utils::Vector3d CoMdot (const biorbd::rigidbody::GeneralizedCoordinates &Q, const biorbd::rigidbody::GeneralizedVelocity &Qdot)
 Return the velocity of the center of mass. More...
 
biorbd::utils::Vector3d CoMddot (const biorbd::rigidbody::GeneralizedCoordinates &Q, const biorbd::rigidbody::GeneralizedVelocity &Qdot, const biorbd::rigidbody::GeneralizedAcceleration &Qddot)
 Return the acceleration of the center of mass. More...
 
std::vector< biorbd::utils::Vector3dCoMdotBySegment (const biorbd::rigidbody::GeneralizedCoordinates &Q, const biorbd::rigidbody::GeneralizedVelocity &Qdot, bool updateKin=true)
 Return the velocity of the center of mass of each segment. More...
 
biorbd::utils::Vector3d CoMdotBySegment (const biorbd::rigidbody::GeneralizedCoordinates &Q, const biorbd::rigidbody::GeneralizedVelocity &Qdot, const unsigned int idx, bool updateKin=true)
 Return the velocity of the center of mass of segment idx. More...
 
std::vector< biorbd::utils::Vector3dCoMddotBySegment (const biorbd::rigidbody::GeneralizedCoordinates &Q, const biorbd::rigidbody::GeneralizedVelocity &Qdot, const biorbd::rigidbody::GeneralizedAcceleration &Qddot, bool updateKin=true)
 Return the acceleration of the center of mass of each segment. More...
 
biorbd::utils::Vector3d CoMddotBySegment (const biorbd::rigidbody::GeneralizedCoordinates &Q, const biorbd::rigidbody::GeneralizedVelocity &Qdot, const biorbd::rigidbody::GeneralizedAcceleration &Qddot, const unsigned int idx, bool updateKin=true)
 Return the acceleration of the center of mass of segment idx. More...
 
biorbd::utils::Matrix CoMJacobian (const biorbd::rigidbody::GeneralizedCoordinates &Q)
 Return the jacobian matrix of the center of mass. More...
 
std::vector< std::vector< biorbd::utils::Vector3d > > meshPoints (const biorbd::rigidbody::GeneralizedCoordinates &Q, bool updateKin=true)
 Return the vertices of the mesh for all segments in global reference frame. More...
 
std::vector< biorbd::utils::Vector3dmeshPoints (const biorbd::rigidbody::GeneralizedCoordinates &Q, unsigned int idx, bool updateKin=true)
 Return the vertices of the mesh for the segment idx. More...
 
std::vector< biorbd::utils::MatrixmeshPointsInMatrix (const biorbd::rigidbody::GeneralizedCoordinates &Q, bool updateKin=true)
 Return all the vertices of the mesh points in a matrix. More...
 
std::vector< std::vector< MeshFace > > meshFaces () const
 Return the mesh faces for all the segments. More...
 
const std::vector< biorbd::rigidbody::MeshFace > & meshFaces (unsigned int idx) const
 Return the mesh faces for segment idx. More...
 
std::vector< biorbd::rigidbody::Meshmesh () const
 Return the segment mesh. More...
 
const biorbd::rigidbody::Meshmesh (unsigned int idx) const
 Return the segment mesh for segment idx. More...
 
biorbd::utils::Vector3d angularMomentum (const biorbd::rigidbody::GeneralizedCoordinates &Q, const biorbd::rigidbody::GeneralizedVelocity &Qdot, bool updateKin=true)
 Calculate the angular momentum of the center of mass. More...
 
biorbd::utils::Matrix massMatrix (const biorbd::rigidbody::GeneralizedCoordinates &Q, bool updateKin=true)
 Get the mass matrix at a given position Q. More...
 
biorbd::utils::Vector3d CalcAngularMomentum (const biorbd::rigidbody::GeneralizedCoordinates &Q, const biorbd::rigidbody::GeneralizedVelocity &Qdot, bool updateKin)
 Calculate the angular momentum of the center of mass. More...
 
biorbd::utils::Vector3d CalcAngularMomentum (const biorbd::rigidbody::GeneralizedCoordinates &Q, const biorbd::rigidbody::GeneralizedVelocity &Qdot, const biorbd::rigidbody::GeneralizedAcceleration &Qddot, bool updateKin)
 Calculate the angular momentum of the center of mass. More...
 
std::vector< biorbd::utils::Vector3dCalcSegmentsAngularMomentum (const biorbd::rigidbody::GeneralizedCoordinates &Q, const biorbd::rigidbody::GeneralizedVelocity &Qdot, bool updateKin)
 Calculate the segment center of mass angular momentum. More...
 
std::vector< biorbd::utils::Vector3dCalcSegmentsAngularMomentum (const biorbd::rigidbody::GeneralizedCoordinates &Q, const biorbd::rigidbody::GeneralizedVelocity &Qdot, const biorbd::rigidbody::GeneralizedAcceleration &Qddot, bool updateKin)
 Calculate the segment center of mass angular momentum. More...
 
void CalcMatRotJacobian (const biorbd::rigidbody::GeneralizedCoordinates &Q, unsigned int segmentIdx, const RigidBodyDynamics::Math::Matrix3d &rotation, RigidBodyDynamics::Math::MatrixNd &G, bool updateKin)
 Calculate the jacobian matrix of a rotation matrix. More...
 
biorbd::rigidbody::GeneralizedVelocity computeQdot (const biorbd::rigidbody::GeneralizedCoordinates &Q, const biorbd::rigidbody::GeneralizedCoordinates &QDot, const double k_stab=1)
 Return the derivate of Q in function of Qdot (if not Quaternion, Qdot is directly returned) More...
 
biorbd::rigidbody::GeneralizedTorque InverseDynamics (const biorbd::rigidbody::GeneralizedCoordinates &Q, const biorbd::rigidbody::GeneralizedVelocity &QDot, const biorbd::rigidbody::GeneralizedAcceleration &QDDot, std::vector< biorbd::utils::SpatialVector > *f_ext=nullptr)
 Interface for the inverse dynamics of RBDL. More...
 
biorbd::rigidbody::GeneralizedAcceleration ForwardDynamics (const biorbd::rigidbody::GeneralizedCoordinates &Q, const biorbd::rigidbody::GeneralizedVelocity &QDot, const biorbd::rigidbody::GeneralizedTorque &Tau, std::vector< biorbd::utils::SpatialVector > *f_ext=nullptr)
 Interface for the forward dynamics of RBDL. More...
 
biorbd::rigidbody::GeneralizedAcceleration ForwardDynamicsConstraintsDirect (const biorbd::rigidbody::GeneralizedCoordinates &Q, const biorbd::rigidbody::GeneralizedVelocity &QDot, const biorbd::rigidbody::GeneralizedTorque &Tau, biorbd::rigidbody::Contacts &CS, std::vector< biorbd::utils::SpatialVector > *f_ext=nullptr)
 Interface for the forward dynamics with contact of RBDL. More...
 
biorbd::utils::Vector ContactForcesFromForwardDynamicsConstraintsDirect (const biorbd::rigidbody::GeneralizedCoordinates &Q, const biorbd::rigidbody::GeneralizedVelocity &QDot, const biorbd::rigidbody::GeneralizedTorque &Tau, std::vector< biorbd::utils::SpatialVector > *f_ext=nullptr)
 Interface for contacts of the forward dynamics with contact of RBDL. More...
 
biorbd::rigidbody::GeneralizedAcceleration ForwardDynamicsConstraintsDirect (const biorbd::rigidbody::GeneralizedCoordinates &Q, const biorbd::rigidbody::GeneralizedVelocity &QDot, const biorbd::rigidbody::GeneralizedTorque &Tau, std::vector< biorbd::utils::SpatialVector > *f_ext=nullptr)
 Interface for the forward dynamics with contact of RBDL. More...
 
biorbd::rigidbody::GeneralizedVelocity ComputeConstraintImpulsesDirect (const biorbd::rigidbody::GeneralizedCoordinates &Q, const biorbd::rigidbody::GeneralizedVelocity &QDotPre)
 Compute the QDot post from an impact. More...
 
void checkGeneralizedDimensions (const biorbd::rigidbody::GeneralizedCoordinates *Q=nullptr, const biorbd::rigidbody::GeneralizedVelocity *Qdot=nullptr, const biorbd::rigidbody::GeneralizedAcceleration *Qddot=nullptr, const biorbd::rigidbody::GeneralizedTorque *torque=nullptr)
 Check for the Generalized coordinates, velocities, acceleration and torque dimensions. More...
 

Protected Member Functions

RigidBodyDynamics::Math::SpatialTransform CalcBodyWorldTransformation (const biorbd::rigidbody::GeneralizedCoordinates &Q, const unsigned int segmentIdx, bool updateKin=true)
 Calculate the joint coordinate system (JCS) in global reference frame of a specified segment. More...
 
RigidBodyDynamics::Math::SpatialTransform CalcBodyWorldTransformation (const unsigned int segmentIdx) const
 Calculate the joint coordinate system (JCS) in global of a specified segment. More...
 
std::vector< biorbd::utils::Vector3dmeshPoints (const std::vector< biorbd::utils::RotoTrans > &RT, unsigned int idx) const
 Return the mesh vertices of segment idx. More...
 

Protected Attributes

std::shared_ptr< std::vector< biorbd::rigidbody::Segment > > m_segments
 All the articulations.
 
std::shared_ptr< unsigned int > m_nbRoot
 The number of DoF on the root segment.
 
std::shared_ptr< unsigned int > m_nbDof
 The total number of degrees of freedom

 
std::shared_ptr< unsigned int > m_nbQ
 The total number of Q.
 
std::shared_ptr< unsigned int > m_nbQdot
 The total number of Qdot.
 
std::shared_ptr< unsigned int > m_nbQddot
 The total number of Qddot.
 
std::shared_ptr< unsigned int > m_nRotAQuat
 The number of segments per quaternion.
 
std::shared_ptr< bool > m_isKinematicsComputed
 If the kinematics are computed.
 
std::shared_ptr< double > m_totalMass
 Mass of all the bodies combined.
 

Detailed Description

This is the core of the musculoskeletal model in biorbd.

Definition at line 38 of file Joints.h.

Constructor & Destructor Documentation

◆ Joints()

biorbd::rigidbody::Joints::Joints ( const biorbd::rigidbody::Joints other)

Construct a joint model from another model.

Parameters
otherThe other joint model

Definition at line 41 of file Joints.cpp.

Member Function Documentation

◆ AddSegment() [1/2]

unsigned int biorbd::rigidbody::Joints::AddSegment ( const biorbd::utils::String segmentName,
const biorbd::utils::String parentName,
const biorbd::utils::String translationSequence,
const biorbd::utils::String rotationSequence,
const std::vector< biorbd::utils::Range > &  QRanges,
const std::vector< biorbd::utils::Range > &  QDotRanges,
const std::vector< biorbd::utils::Range > &  QDDotRanges,
const biorbd::rigidbody::SegmentCharacteristics characteristics,
const RigidBodyDynamics::Math::SpatialTransform &  centreOfRotation,
int  forcePlates = -1 
)

Add a segment to the model.

Parameters
segmentNameName of the segment
parentNameName of the segment parent
translationSequenceThe translation sequence
rotationSequenceEuler sequence of rotations
QRangesRanges of the translations and rotations dof. The length of QRanges must be equal to length of translations and rotations
QDotRangesRanges of the translations and rotations dof velocity. The length of QDotRanges must be equal to length of translations and rotations
QDDotRangesRanges of the translations and rotations dof acceleration. The length of QDDotRanges must be equal to length of translations and rotations
characteristicsThe characteristics of the semgent (mass, center of mass, inertia of the segment, etc)
centreOfRotationTransformation of the parent to child
forcePlatesThe number of the force platform attached to the Segment (if -1 no force platform is attached)

Definition at line 125 of file Joints.cpp.

◆ AddSegment() [2/2]

unsigned int biorbd::rigidbody::Joints::AddSegment ( const biorbd::utils::String segmentName,
const biorbd::utils::String parentName,
const biorbd::utils::String translationSequence,
const std::vector< biorbd::utils::Range > &  QRanges,
const std::vector< biorbd::utils::Range > &  QDotRanges,
const std::vector< biorbd::utils::Range > &  QDDotRanges,
const biorbd::rigidbody::SegmentCharacteristics characteristics,
const RigidBodyDynamics::Math::SpatialTransform &  centreOfRotation,
int  forcePlates = -1 
)

Add a segment to the model.

Parameters
segmentNameName of the segment
parentNameName of the segment parent
translationSequenceThe translation sequence
QRangesRanges of the translations and rotations dof. The length of QRanges must be equal to length of translations and rotations
QDotRangesRanges of the translations and rotations dof velocity. The length of QDotRanges must be equal to length of translations and rotations
QDDotRangesRanges of the translations and rotations dof acceleration. The length of QDDotRanges must be equal to length of translations and rotations
characteristicsThe characteristics of the semgent (mass, center of mass, inertia of the segment, etc)
centreOfRotationTransformation of the parent to child
forcePlatesThe number of the force platform attached to the Segment (if -1 no force platform is attached)

Definition at line 155 of file Joints.cpp.

◆ allGlobalJCS() [1/2]

std::vector< biorbd::utils::RotoTrans > biorbd::rigidbody::Joints::allGlobalJCS ( ) const

Return the joint coordinate system (JCS) in global reference frame at a given Q.

Returns
The JCS in global reference frame

This function assumes kinematics has been already updated

Definition at line 259 of file Joints.cpp.

◆ allGlobalJCS() [2/2]

std::vector< biorbd::utils::RotoTrans > biorbd::rigidbody::Joints::allGlobalJCS ( const biorbd::rigidbody::GeneralizedCoordinates Q)

Return the joint coordinate system (JCS) in global reference frame at a given Q.

Parameters
QThe generalized coordinates
Returns
The JCS in global reference frame at a given Q

Definition at line 252 of file Joints.cpp.

◆ angularMomentum()

biorbd::utils::Vector3d biorbd::rigidbody::Joints::angularMomentum ( const biorbd::rigidbody::GeneralizedCoordinates Q,
const biorbd::rigidbody::GeneralizedVelocity Qdot,
bool  updateKin = true 
)

Calculate the angular momentum of the center of mass.

Parameters
QThe generalized coordinates
QdotThe generalized velocities
updateKinIf the kinematics of the model should be computed
Returns
The angular momentum of the center of mass

Definition at line 488 of file Joints.cpp.

◆ CalcAngularMomentum() [1/2]

biorbd::utils::Vector3d biorbd::rigidbody::Joints::CalcAngularMomentum ( const biorbd::rigidbody::GeneralizedCoordinates Q,
const biorbd::rigidbody::GeneralizedVelocity Qdot,
bool  updateKin 
)

Calculate the angular momentum of the center of mass.

Parameters
QThe generalized coordinates
QdotThe generalized velocities
updateKinIf the kinematics of the model should be computed
Returns
The angular momentum of the center of mass

Definition at line 777 of file Joints.cpp.

◆ CalcAngularMomentum() [2/2]

biorbd::utils::Vector3d biorbd::rigidbody::Joints::CalcAngularMomentum ( const biorbd::rigidbody::GeneralizedCoordinates Q,
const biorbd::rigidbody::GeneralizedVelocity Qdot,
const biorbd::rigidbody::GeneralizedAcceleration Qddot,
bool  updateKin 
)

Calculate the angular momentum of the center of mass.

Parameters
QThe generalized coordinates
QdotThe generalized velocities
QddotThe generalized accelerations
updateKinIf the kinematics of the model should be computed
Returns
The angular momentum of the center of mass

Definition at line 795 of file Joints.cpp.

◆ CalcBodyWorldTransformation() [1/2]

RigidBodyDynamics::Math::SpatialTransform biorbd::rigidbody::Joints::CalcBodyWorldTransformation ( const biorbd::rigidbody::GeneralizedCoordinates Q,
const unsigned int  segmentIdx,
bool  updateKin = true 
)
protected

Calculate the joint coordinate system (JCS) in global reference frame of a specified segment.

Parameters
QThe generalized coordinates
segmentIdxThe index of the segment
updateKinIf the kinematics of the model should be computed
Returns
The JCS of the segment in global reference frame

Definition at line 433 of file Joints.cpp.

◆ CalcBodyWorldTransformation() [2/2]

RigidBodyDynamics::Math::SpatialTransform biorbd::rigidbody::Joints::CalcBodyWorldTransformation ( const unsigned int  segmentIdx) const
protected

Calculate the joint coordinate system (JCS) in global of a specified segment.

Parameters
segmentIdxThe index of the segment
Returns
The JCS in global

This function assumes that the kinematics was previously updated

Definition at line 445 of file Joints.cpp.

◆ CalcMatRotJacobian()

void biorbd::rigidbody::Joints::CalcMatRotJacobian ( const biorbd::rigidbody::GeneralizedCoordinates Q,
unsigned int  segmentIdx,
const RigidBodyDynamics::Math::Matrix3d &  rotation,
RigidBodyDynamics::Math::MatrixNd &  G,
bool  updateKin 
)

Calculate the jacobian matrix of a rotation matrix.

Parameters
QThe generalized coordinates
segmentIdxThe index of the segment
rotationThe rotation matrix
GThe jacobian matrix (output)
updateKinIf the kinematics of the model should be computed

Definition at line 1072 of file Joints.cpp.

◆ CalcSegmentsAngularMomentum() [1/2]

std::vector< biorbd::utils::Vector3d > biorbd::rigidbody::Joints::CalcSegmentsAngularMomentum ( const biorbd::rigidbody::GeneralizedCoordinates Q,
const biorbd::rigidbody::GeneralizedVelocity Qdot,
bool  updateKin 
)

Calculate the segment center of mass angular momentum.

Parameters
QThe generalized coordinates
QdotThe generalized velocities
updateKinIf the kinematics of the model should be computed
Returns
The segments center of mass angular momentum

Definition at line 817 of file Joints.cpp.

◆ CalcSegmentsAngularMomentum() [2/2]

std::vector< biorbd::utils::Vector3d > biorbd::rigidbody::Joints::CalcSegmentsAngularMomentum ( const biorbd::rigidbody::GeneralizedCoordinates Q,
const biorbd::rigidbody::GeneralizedVelocity Qdot,
const biorbd::rigidbody::GeneralizedAcceleration Qddot,
bool  updateKin 
)

Calculate the segment center of mass angular momentum.

Parameters
QThe generalized coordinates
QdotThe generalized velocities
QddotThe generalized accelerations
updateKinIf the kinematics of the model should be computed
Returns
The segments center of mass angular momentum

Definition at line 853 of file Joints.cpp.

◆ checkGeneralizedDimensions()

void biorbd::rigidbody::Joints::checkGeneralizedDimensions ( const biorbd::rigidbody::GeneralizedCoordinates Q = nullptr,
const biorbd::rigidbody::GeneralizedVelocity Qdot = nullptr,
const biorbd::rigidbody::GeneralizedAcceleration Qddot = nullptr,
const biorbd::rigidbody::GeneralizedTorque torque = nullptr 
)

Check for the Generalized coordinates, velocities, acceleration and torque dimensions.

Parameters
QThe generalized coordinates
QdotThe generalized velocities
QddotThe generalized accelerations
torqueThe generalized torques

Definition at line 1136 of file Joints.cpp.

◆ CoM()

biorbd::utils::Vector3d biorbd::rigidbody::Joints::CoM ( const biorbd::rigidbody::GeneralizedCoordinates Q,
bool  updateKin = true 
)

Return the position of the center of mass.

Parameters
QThe generalized coordinates
updateKinIf the kinematics of the model should be computed
Returns
The position of the center of mass

Definition at line 464 of file Joints.cpp.

◆ CoMbySegment() [1/2]

std::vector< biorbd::rigidbody::NodeSegment > biorbd::rigidbody::Joints::CoMbySegment ( const biorbd::rigidbody::GeneralizedCoordinates Q,
bool  updateKin = true 
)

Return the position of the center of mass of each segment.

Parameters
QThe generalized coordinates
updateKinIf the kinematics of the model should be computed
Returns
The position of the center of mass of each segment

Definition at line 576 of file Joints.cpp.

◆ CoMbySegment() [2/2]

biorbd::utils::Vector3d biorbd::rigidbody::Joints::CoMbySegment ( const biorbd::rigidbody::GeneralizedCoordinates Q,
const unsigned int  idx,
bool  updateKin = true 
)

Return the position of the center of mass of segment idx.

Parameters
QThe generalized coordinates
idxThe index of the segment
updateKinIf the kinematics of the model should be computed
Returns
The position of the center of mass of segment idx

Definition at line 603 of file Joints.cpp.

◆ CoMbySegmentInMatrix()

biorbd::utils::Matrix biorbd::rigidbody::Joints::CoMbySegmentInMatrix ( const biorbd::rigidbody::GeneralizedCoordinates Q,
bool  updateKin = true 
)

Return the position of the center of mass of each segment in a matrix.

Parameters
QThe generalized coordinates
updateKinIf the kinematics of the model should be computed
Returns
The position of the center of mass of each segment

Definition at line 590 of file Joints.cpp.

◆ CoMddot()

Return the acceleration of the center of mass.

Parameters
QThe generalized coordinates
QdotThe generalized velocities
QddotThe acceleration variables
Returns
The acceleration of the center of mass

Definition at line 531 of file Joints.cpp.

◆ CoMddotBySegment() [1/2]

std::vector< biorbd::utils::Vector3d > biorbd::rigidbody::Joints::CoMddotBySegment ( const biorbd::rigidbody::GeneralizedCoordinates Q,
const biorbd::rigidbody::GeneralizedVelocity Qdot,
const biorbd::rigidbody::GeneralizedAcceleration Qddot,
bool  updateKin = true 
)

Return the acceleration of the center of mass of each segment.

Parameters
QThe generalized coordinates
QdotThe generalized velocities
QddotThe acceleration variables
updateKinIf the kinematics of the model should be computed
Returns
The acceleration of the center of mass of each segment

Definition at line 648 of file Joints.cpp.

◆ CoMddotBySegment() [2/2]

biorbd::utils::Vector3d biorbd::rigidbody::Joints::CoMddotBySegment ( const biorbd::rigidbody::GeneralizedCoordinates Q,
const biorbd::rigidbody::GeneralizedVelocity Qdot,
const biorbd::rigidbody::GeneralizedAcceleration Qddot,
const unsigned int  idx,
bool  updateKin = true 
)

Return the acceleration of the center of mass of segment idx.

Parameters
QThe generalized coordinates
QdotThe generalized velocities
QddotThe acceleration variables
idxThe segment identification
updateKinIf the kinematics of the model should be computed
Returns
The acceleration of the center of mass of segment idx

Definition at line 666 of file Joints.cpp.

◆ CoMdot()

biorbd::utils::Vector3d biorbd::rigidbody::Joints::CoMdot ( const biorbd::rigidbody::GeneralizedCoordinates Q,
const biorbd::rigidbody::GeneralizedVelocity Qdot 
)

Return the velocity of the center of mass.

Parameters
QThe generalized coordinates
QdotThe generalized velocities
Returns
The velocity of the center of mass

Definition at line 506 of file Joints.cpp.

◆ CoMdotBySegment() [1/2]

std::vector< biorbd::utils::Vector3d > biorbd::rigidbody::Joints::CoMdotBySegment ( const biorbd::rigidbody::GeneralizedCoordinates Q,
const biorbd::rigidbody::GeneralizedVelocity Qdot,
bool  updateKin = true 
)

Return the velocity of the center of mass of each segment.

Parameters
QThe generalized coordinates
QdotThe generalized velocities
updateKinIf the kinematics of the model should be computed
Returns
The velocity of the center of mass of each segment

Definition at line 618 of file Joints.cpp.

◆ CoMdotBySegment() [2/2]

biorbd::utils::Vector3d biorbd::rigidbody::Joints::CoMdotBySegment ( const biorbd::rigidbody::GeneralizedCoordinates Q,
const biorbd::rigidbody::GeneralizedVelocity Qdot,
const unsigned int  idx,
bool  updateKin = true 
)

Return the velocity of the center of mass of segment idx.

Parameters
QThe generalized coordinates
QdotThe generalized velocities
idxThe index of the segment
updateKinIf the kinematics of the model should be computed
Returns
The velocity of the center of mass of segment idx

Definition at line 635 of file Joints.cpp.

◆ CoMJacobian()

biorbd::utils::Matrix biorbd::rigidbody::Joints::CoMJacobian ( const biorbd::rigidbody::GeneralizedCoordinates Q)

Return the jacobian matrix of the center of mass.

Parameters
QThe generalized coordinates
Returns
The jacobian matrix of the center of mass

Definition at line 547 of file Joints.cpp.

◆ ComputeConstraintImpulsesDirect()

biorbd::rigidbody::GeneralizedVelocity biorbd::rigidbody::Joints::ComputeConstraintImpulsesDirect ( const biorbd::rigidbody::GeneralizedCoordinates Q,
const biorbd::rigidbody::GeneralizedVelocity QDotPre 
)

Compute the QDot post from an impact.

Parameters
QThe Generalized Coordinates
QDotPreThe Generalized Velocities before impact
Returns
The Generalized Velocities post acceleration

Definition at line 1020 of file Joints.cpp.

◆ computeQdot()

biorbd::rigidbody::GeneralizedVelocity biorbd::rigidbody::Joints::computeQdot ( const biorbd::rigidbody::GeneralizedCoordinates Q,
const biorbd::rigidbody::GeneralizedCoordinates QDot,
const double  k_stab = 1 
)

Return the derivate of Q in function of Qdot (if not Quaternion, Qdot is directly returned)

Parameters
QThe generalized coordinates
QDotThe generalized velocities
k_stab
Returns
The derivate of Q in function of Qdot

Definition at line 892 of file Joints.cpp.

◆ ContactForcesFromForwardDynamicsConstraintsDirect()

biorbd::utils::Vector biorbd::rigidbody::Joints::ContactForcesFromForwardDynamicsConstraintsDirect ( const biorbd::rigidbody::GeneralizedCoordinates Q,
const biorbd::rigidbody::GeneralizedVelocity QDot,
const biorbd::rigidbody::GeneralizedTorque Tau,
std::vector< biorbd::utils::SpatialVector > *  f_ext = nullptr 
)

Interface for contacts of the forward dynamics with contact of RBDL.

Parameters
QThe Generalized Coordinates
QDotThe Generalized Velocities
TauThe Generalized Torques
f_extExternal force acting on the system if there are any
Returns
The Contraint set

Definition at line 990 of file Joints.cpp.

◆ DeepCopy() [1/2]

biorbd::rigidbody::Joints biorbd::rigidbody::Joints::DeepCopy ( ) const

Deep copy of the joints.

Returns
Copy of the joints

Definition at line 61 of file Joints.cpp.

◆ DeepCopy() [2/2]

void biorbd::rigidbody::Joints::DeepCopy ( const biorbd::rigidbody::Joints other)

Deep copy of the joints.

Parameters
otherThe joints to copy

Definition at line 68 of file Joints.cpp.

◆ dispatchedForce() [1/2]

std::vector< RigidBodyDynamics::Math::SpatialVector > biorbd::rigidbody::Joints::dispatchedForce ( std::vector< biorbd::utils::SpatialVector > &  sv) const

Dispatch the forces from the force plate in a spatial vector.

Parameters
svOne spatial vector per force platform
Returns
A spatial vector with the forces

Definition at line 217 of file Joints.cpp.

◆ dispatchedForce() [2/2]

std::vector< RigidBodyDynamics::Math::SpatialVector > biorbd::rigidbody::Joints::dispatchedForce ( std::vector< std::vector< biorbd::utils::SpatialVector >> &  spatialVector,
unsigned int  frame 
) const

Dispatch the forces from the force plate in a vector.

Parameters
spatialVectorThe values over time of one spatial vector per force platform
frameThe frame to dispatch
Returns
A spatial vector with the forces

Definition at line 204 of file Joints.cpp.

◆ ForwardDynamics()

biorbd::rigidbody::GeneralizedAcceleration biorbd::rigidbody::Joints::ForwardDynamics ( const biorbd::rigidbody::GeneralizedCoordinates Q,
const biorbd::rigidbody::GeneralizedVelocity QDot,
const biorbd::rigidbody::GeneralizedTorque Tau,
std::vector< biorbd::utils::SpatialVector > *  f_ext = nullptr 
)

Interface for the forward dynamics of RBDL.

Parameters
QThe Generalized Coordinates
QDotThe Generalized Velocities
TauThe Generalized Torques
f_extExternal force acting on the system if there are any
Returns
The Generalized Accelerations

Definition at line 953 of file Joints.cpp.

◆ ForwardDynamicsConstraintsDirect() [1/2]

biorbd::rigidbody::GeneralizedAcceleration biorbd::rigidbody::Joints::ForwardDynamicsConstraintsDirect ( const biorbd::rigidbody::GeneralizedCoordinates Q,
const biorbd::rigidbody::GeneralizedVelocity QDot,
const biorbd::rigidbody::GeneralizedTorque Tau,
biorbd::rigidbody::Contacts CS,
std::vector< biorbd::utils::SpatialVector > *  f_ext = nullptr 
)

Interface for the forward dynamics with contact of RBDL.

Parameters
QThe Generalized Coordinates
QDotThe Generalized Velocities
TauThe Generalized Torques
CSThe Constraint set that will be filled
f_extExternal force acting on the system if there are any
Returns
The Generalized Accelerations

Definition at line 971 of file Joints.cpp.

◆ ForwardDynamicsConstraintsDirect() [2/2]

biorbd::rigidbody::GeneralizedAcceleration biorbd::rigidbody::Joints::ForwardDynamicsConstraintsDirect ( const biorbd::rigidbody::GeneralizedCoordinates Q,
const biorbd::rigidbody::GeneralizedVelocity QDot,
const biorbd::rigidbody::GeneralizedTorque Tau,
std::vector< biorbd::utils::SpatialVector > *  f_ext = nullptr 
)

Interface for the forward dynamics with contact of RBDL.

Parameters
QThe Generalized Coordinates
QDotThe Generalized Velocities
TauThe Generalized Torques
f_extExternal force acting on the system if there are any
Returns
The Generalized Accelerations

Definition at line 1001 of file Joints.cpp.

◆ GetBodyBiorbdId()

int biorbd::rigidbody::Joints::GetBodyBiorbdId ( const biorbd::utils::String segmentName) const

Return the biorbd body identification.

Parameters
segmentNameThe name of the segment
Returns
The biorbd body identification

Definition at line 245 of file Joints.cpp.

◆ getDofIndex()

unsigned int biorbd::rigidbody::Joints::getDofIndex ( const biorbd::utils::String SegmentName,
const biorbd::utils::String dofName 
)

Return the index of a DoF in a segment.

Parameters
SegmentNameThe name of the Segment
dofNameThe name of the degree of freedom (DoF)
Returns
The index of a DoF in a segment

Definition at line 1037 of file Joints.cpp.

◆ getGravity()

biorbd::utils::Vector3d biorbd::rigidbody::Joints::getGravity ( ) const

Get the current gravity.

Returns
The current gravity

Definition at line 178 of file Joints.cpp.

◆ globalJCS() [1/4]

biorbd::utils::RotoTrans biorbd::rigidbody::Joints::globalJCS ( const biorbd::rigidbody::GeneralizedCoordinates Q,
const biorbd::utils::String name 
)

Return the joint coordinate system (JCS) for the segment in global reference frame at a given Q.

Parameters
QThe generalized coordinates
nameThe name of the segment
Returns
The JCS of the segment in global reference frame at a given Q

Definition at line 267 of file Joints.cpp.

◆ globalJCS() [2/4]

biorbd::utils::RotoTrans biorbd::rigidbody::Joints::globalJCS ( const biorbd::rigidbody::GeneralizedCoordinates Q,
unsigned int  idx 
)

Return the joint coordinate system (JCS) for the segment idx in global reference frame at a given Q.

Parameters
QThe generalized coordinates
idxThe index of the segment
Returns
The JCS of the segment idx in global reference frame at a given Q

Definition at line 275 of file Joints.cpp.

◆ globalJCS() [3/4]

biorbd::utils::RotoTrans biorbd::rigidbody::Joints::globalJCS ( const biorbd::utils::String name) const

Return the joint coordinate system (JCS) for the segment in global reference.

Parameters
nameThe name of the segment
Returns
The JCS of the segment in global reference frame

This function assumes kinematics has been already updated

Definition at line 284 of file Joints.cpp.

◆ globalJCS() [4/4]

biorbd::utils::RotoTrans biorbd::rigidbody::Joints::globalJCS ( unsigned int  idx) const

Return the joint coordinate system (JCS) for the segment idx in global reference.

Parameters
idxThe index of the segment
Returns
The JCS of the segment idx in global reference frame

This function assumes kinematics has been already updated

Definition at line 289 of file Joints.cpp.

◆ InverseDynamics()

biorbd::rigidbody::GeneralizedTorque biorbd::rigidbody::Joints::InverseDynamics ( const biorbd::rigidbody::GeneralizedCoordinates Q,
const biorbd::rigidbody::GeneralizedVelocity QDot,
const biorbd::rigidbody::GeneralizedAcceleration QDDot,
std::vector< biorbd::utils::SpatialVector > *  f_ext = nullptr 
)

Interface for the inverse dynamics of RBDL.

Parameters
QThe Generalized Coordinates
QDotThe Generalized Velocities
QDDotThe Generalzed Acceleration
f_extExternal force acting on the system if there are any
Returns
The Generalized Torques

Definition at line 935 of file Joints.cpp.

◆ localJCS() [1/3]

std::vector< biorbd::utils::RotoTrans > biorbd::rigidbody::Joints::localJCS ( ) const

Return all the joint coordinate system (JCS) in its parent reference frame.

Returns
All the JCS in parent reference frame

Definition at line 295 of file Joints.cpp.

◆ localJCS() [2/3]

biorbd::utils::RotoTrans biorbd::rigidbody::Joints::localJCS ( const biorbd::utils::String name) const

Return the joint coordinate system (JCS) of the segment its parent reference frame.

Parameters
nameThe name of the segment
Returns
The JCS of the segment in parent reference frame

Definition at line 303 of file Joints.cpp.

◆ localJCS() [3/3]

biorbd::utils::RotoTrans biorbd::rigidbody::Joints::localJCS ( const unsigned int  idx) const

Return the joint coordinate system (JCS) of the segment idx its parent reference frame.

Parameters
idxThe index of the segment
Returns
The JCS of the segment idx in parent reference frame

Definition at line 306 of file Joints.cpp.

◆ mass()

double biorbd::rigidbody::Joints::mass ( ) const

Return the total mass of the model.

Returns
The toal mass of the model

Definition at line 121 of file Joints.cpp.

◆ massMatrix()

biorbd::utils::Matrix biorbd::rigidbody::Joints::massMatrix ( const biorbd::rigidbody::GeneralizedCoordinates Q,
bool  updateKin = true 
)

Get the mass matrix at a given position Q.

Parameters
QThe generalized coordinates
updateKinIf the kinematics should be updated
Returns
The mass matrix

Definition at line 496 of file Joints.cpp.

◆ mesh() [1/2]

std::vector< biorbd::rigidbody::Mesh > biorbd::rigidbody::Joints::mesh ( ) const

Return the segment mesh.

Returns
The segment mesh

Definition at line 764 of file Joints.cpp.

◆ mesh() [2/2]

const biorbd::rigidbody::Mesh & biorbd::rigidbody::Joints::mesh ( unsigned int  idx) const

Return the segment mesh for segment idx.

Parameters
idxThe index of the segment
Returns
The Segment mesh for segment idx

Definition at line 772 of file Joints.cpp.

◆ meshFaces() [1/2]

std::vector< std::vector< biorbd::rigidbody::MeshFace > > biorbd::rigidbody::Joints::meshFaces ( ) const

Return the mesh faces for all the segments.

Returns
The mesh faces for all the segments

Definition at line 752 of file Joints.cpp.

◆ meshFaces() [2/2]

const std::vector< biorbd::rigidbody::MeshFace > & biorbd::rigidbody::Joints::meshFaces ( unsigned int  idx) const

Return the mesh faces for segment idx.

Parameters
idxThe index of the segment
Returns
The mesh face for segment idx

Definition at line 759 of file Joints.cpp.

◆ meshPoints() [1/3]

std::vector< std::vector< biorbd::utils::Vector3d > > biorbd::rigidbody::Joints::meshPoints ( const biorbd::rigidbody::GeneralizedCoordinates Q,
bool  updateKin = true 
)

Return the vertices of the mesh for all segments in global reference frame.

Parameters
QThe generalized coordinates
updateKinIf the kinematics of the model should be computed
Returns
The vertices of the for all segments

Definition at line 682 of file Joints.cpp.

◆ meshPoints() [2/3]

std::vector< biorbd::utils::Vector3d > biorbd::rigidbody::Joints::meshPoints ( const biorbd::rigidbody::GeneralizedCoordinates Q,
unsigned int  idx,
bool  updateKin = true 
)

Return the vertices of the mesh for the segment idx.

Parameters
QThe generalized coordinates
idxThe index of the segment
updateKinIf the kinematics of the model should be computed
Returns
The vertices of the of the segment idx

Definition at line 700 of file Joints.cpp.

◆ meshPoints() [3/3]

std::vector< biorbd::utils::Vector3d > biorbd::rigidbody::Joints::meshPoints ( const std::vector< biorbd::utils::RotoTrans > &  RT,
unsigned int  idx 
) const
protected

Return the mesh vertices of segment idx.

Parameters
RTThe RotoTrans of the segment
idxThe index of the segment
Returns
The mesh vertices attached to a segment idx

Definition at line 737 of file Joints.cpp.

◆ meshPointsInMatrix()

std::vector< biorbd::utils::Matrix > biorbd::rigidbody::Joints::meshPointsInMatrix ( const biorbd::rigidbody::GeneralizedCoordinates Q,
bool  updateKin = true 
)

Return all the vertices of the mesh points in a matrix.

Parameters
QThe generalized coordinates
updateKinIf the kinematics of the model should be computed
Returns
All the vertices

Definition at line 716 of file Joints.cpp.

◆ nameDof()

std::vector< biorbd::utils::String > biorbd::rigidbody::Joints::nameDof ( ) const

Return the names of the degree of freedom (DoF)

Returns
The names of the DoF

Definition at line 91 of file Joints.cpp.

◆ nbDof()

unsigned int biorbd::rigidbody::Joints::nbDof ( ) const

Return the number of degrees of freedom (DoF)

Returns
The number of DoF

Definition at line 87 of file Joints.cpp.

◆ nbGeneralizedTorque()

unsigned int biorbd::rigidbody::Joints::nbGeneralizedTorque ( ) const

Return the number of generalized torque.

Returns
The number of generalized torque

Definition at line 84 of file Joints.cpp.

◆ nbQ()

unsigned int biorbd::rigidbody::Joints::nbQ ( ) const

Return the number of generalized coordinates (Q)

Returns
The number of Q

Definition at line 108 of file Joints.cpp.

◆ nbQddot()

unsigned int biorbd::rigidbody::Joints::nbQddot ( ) const

Return the number of generalized acceleration (Qddot)

Returns
The number of Qddot

Definition at line 114 of file Joints.cpp.

◆ nbQdot()

unsigned int biorbd::rigidbody::Joints::nbQdot ( ) const

Return the number of generalized velocities (Qdot)

Returns
The number of Qdot

Definition at line 111 of file Joints.cpp.

◆ nbQuat()

unsigned int biorbd::rigidbody::Joints::nbQuat ( ) const

Return the number of segments that are described using quaternions.

Returns
The number number of segments

Definition at line 888 of file Joints.cpp.

◆ nbRoot()

unsigned int biorbd::rigidbody::Joints::nbRoot ( ) const

Return the dof on the root.

Returns
The dof on the root

Definition at line 117 of file Joints.cpp.

◆ nbSegment()

unsigned int biorbd::rigidbody::Joints::nbSegment ( ) const

Return the actual number of segment.

Returns
The actual number of segment

Definition at line 199 of file Joints.cpp.

◆ projectPoint() [1/3]

biorbd::rigidbody::NodeSegment biorbd::rigidbody::Joints::projectPoint ( const biorbd::rigidbody::GeneralizedCoordinates Q,
const biorbd::rigidbody::NodeSegment n,
bool  updateKin 
)

Return the projected markers from a point corresponding to a marker from the model.

Parameters
QThe generalized coordinates
nA reference to a marker from the model
updateKinIf the kinematics of the model should be computed
Returns
The projected markers from a point corresponding to a marker from the model

Definition at line 361 of file Joints.cpp.

◆ projectPoint() [2/3]

biorbd::rigidbody::NodeSegment biorbd::rigidbody::Joints::projectPoint ( const biorbd::rigidbody::GeneralizedCoordinates Q,
const biorbd::utils::Vector3d v,
int  segmentIdx,
const biorbd::utils::String axesToRemove,
bool  updateKin = true 
)

Project a point on specific axis of a segment.

Parameters
QThe generalized coordinates
vThe point to project
segmentIdxThe segment index to project the marker on
axesToRemoveThe axis to remove
updateKinIf the kinematics of the model should be computed
Returns
The position of the projected marker

Definition at line 341 of file Joints.cpp.

◆ projectPoint() [3/3]

std::vector< biorbd::rigidbody::NodeSegment > biorbd::rigidbody::Joints::projectPoint ( const biorbd::rigidbody::GeneralizedCoordinates Q,
const std::vector< biorbd::rigidbody::NodeSegment > &  v,
bool  updateKin = true 
)

Project multiples points on their respective segment.

Parameters
QThe generalized coordinates
vAll the points to project. The number of points must match the number of marker in the joint model
updateKinIf the kinematics of the model should be computed
Returns
The projected markers from points corresponding to markers from the model

Return projected markers from points corresponding to markers from the model. The vector needs to be equal to the number of markers and in the order given by Markers and in global coordinates

Definition at line 311 of file Joints.cpp.

◆ projectPointJacobian() [1/3]

biorbd::utils::Matrix biorbd::rigidbody::Joints::projectPointJacobian ( const biorbd::rigidbody::GeneralizedCoordinates Q,
biorbd::rigidbody::NodeSegment  p,
bool  updateKin 
)

Return the jacobian matrix of the projected markers for a marker from the model.

Parameters
QThe generalized coordinates
pA reference to a marker from the model
updateKinIf the kinematics of the model should be computed
Returns
The jacobian matrix of the projected marker

Definition at line 370 of file Joints.cpp.

◆ projectPointJacobian() [2/3]

biorbd::utils::Matrix biorbd::rigidbody::Joints::projectPointJacobian ( const biorbd::rigidbody::GeneralizedCoordinates Q,
const biorbd::utils::Vector3d v,
int  segmentIdx,
const biorbd::utils::String axesToRemove,
bool  updateKin 
)

Return the Jacobian matrix of a projected marker on the segment segmentIdx.

Parameters
QThe generalized coordinates
vThe marker to project
segmentIdxThe index of the segment to project the marker on
axesToRemoveThe axes to remove
updateKinIf the kinematics of the model should be computed
Returns
The Jacobian matrix of a projected marker on the segment segmentIdx

Definition at line 401 of file Joints.cpp.

◆ projectPointJacobian() [3/3]

std::vector< biorbd::utils::Matrix > biorbd::rigidbody::Joints::projectPointJacobian ( const biorbd::rigidbody::GeneralizedCoordinates Q,
const std::vector< biorbd::rigidbody::NodeSegment > &  v,
bool  updateKin 
)

Return the jacobian matrix of the projected markers.

Parameters
QThe generalized coordinates
vAll the markers. The size of which must match the one in the joint model
updateKinIf the kinematics of the model should be computed
Returns
The jacobian matrix of the projected markers

Return the jacobian matrix of projected markers from points corresponding to markers from the model. The vector needs to be equal to the number of markers and in the order given by Markers and in global coordinates

Definition at line 415 of file Joints.cpp.

◆ segment() [1/2]

const biorbd::rigidbody::Segment & biorbd::rigidbody::Joints::segment ( const biorbd::utils::String name) const

Get a segment of a specific name.

Parameters
nameThe name of the segment to return
Returns
The segment

Definition at line 194 of file Joints.cpp.

◆ segment() [2/2]

const biorbd::rigidbody::Segment & biorbd::rigidbody::Joints::segment ( unsigned int  idx) const

Get a segment of index idx.

Parameters
idxIndex of the segment
Returns
The segment

Definition at line 189 of file Joints.cpp.

◆ setGravity()

void biorbd::rigidbody::Joints::setGravity ( const biorbd::utils::Vector3d newGravity)

Set the gravity.

Parameters
newGravityThe new gravity vector

Definition at line 183 of file Joints.cpp.

◆ UpdateKinematicsCustom()

void biorbd::rigidbody::Joints::UpdateKinematicsCustom ( const biorbd::rigidbody::GeneralizedCoordinates Q = nullptr,
const biorbd::rigidbody::GeneralizedVelocity Qdot = nullptr,
const biorbd::rigidbody::GeneralizedAcceleration Qddot = nullptr 
)

Update the kinematic variables such as body velocities and accelerations in the model to reflect the variables passed to this function.

Parameters
QThe generalized coordinates
QdotThe generalized velocities
QddotThe generalized accelerations

Definition at line 1063 of file Joints.cpp.


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