Functions
RobotDynamics::Utils Namespace Reference

Namespace that contains optional helper functions. More...

Functions

void calcCenterOfMass (Model &model, const Math::VectorNd &q, Math::Vector3d &com, bool update_kinematics=true)
 Computes the Center of Mass (COM) position. More...
 
void calcCenterOfMass (Model &model, const Math::VectorNd &q, Math::FramePoint &com, bool update_kinematics=true)
 Computes the Center of Mass (COM) position. More...
 
void calcCenterOfMass (Model &model, const Math::VectorNd &q, const Math::VectorNd &qdot, double &mass, Math::Vector3d &com, Math::Vector3d *com_velocity=NULL, Math::Vector3d *angular_momentum=NULL, bool update_kinematics=true)
 Computes the Center of Mass (COM) and optionally its linear velocity. More...
 
void calcCenterOfMass (Model &model, const Math::VectorNd &q, const Math::VectorNd &qdot, double &mass, Math::FramePoint &com, Math::FrameVector *com_velocity=nullptr, Math::FrameVector *angular_momentum=nullptr, bool update_kinematics=true)
 Computes the Center of Mass (COM) and optionally its linear velocity and/or angular momentum. More...
 
void calcCenterOfMass (Model &model, const Math::VectorNd &q, const Math::VectorNd &qdot, Math::FramePoint &com, Math::FrameVector *com_velocity=nullptr, bool update_kinematics=true)
 Computes the Center of Mass (COM) and optionally its linear velocity. More...
 
void calcCenterOfMassJacobian (Model &model, const Math::VectorNd &q, Math::MatrixNd &jCom, bool update_kinematics=true)
 Computes the matrix $J_{com}$ such that $v_{com} = J_{com} \dot{q} $. More...
 
void calcCenterOfMassVelocity (Model &model, const Math::VectorNd &q, const Math::VectorNd &qdot, Math::Vector3d &com_vel, bool update_kinematics=true)
 Computes the Center of Mass (COM) velocity in world frame. More...
 
void calcCenterOfMassVelocity (Model &model, const Math::VectorNd &q, const Math::VectorNd &qdot, Math::FrameVector &com_vel, bool update_kinematics=true)
 Computes the Center of Mass (COM) velocity in world frame. More...
 
void calcCenterOfMassVelocity (Model &model, Math::Vector3d &com_vel)
 Computes the Center of Mass (COM) velocity in world frame. More...
 
void calcCenterOfMassVelocity (Model &model, Math::FrameVector &com_vel)
 Computes the Center of Mass (COM) velocity in world frame. More...
 
void calcCentroidalMomentumMatrix (Model &model, const Math::VectorNd &q, Math::MatrixNd &A, bool update_kinematics=true)
 Calculates the centroidal momentum matrix, $ A(q) $ for a model. The centroidal momentum matrix is a $ 6 \times N $ matrix such that the 6dof centroidal momentum vector is computed by,

\[ h = A(q) \dot{q} \]

. More...

 
void calcCentroidalMomentumMatrixDot (Model &model, const Math::VectorNd &q, const Math::VectorNd &qdot, Math::MatrixNd &Adot, bool update_kinematics=true)
 Calculates the time derivative of the centroidal momentum matrix, i.e. the matrix computed by RobotDynamics::Utils::calcCentroidalMomentumMatrix and stores it in the Adot argument. More...
 
Math::SpatialForce calcGravityWrenchOnCenterOfMass (Model &model, const Math::VectorNd &q, bool update_kinematics=true)
 Computes the gravitational wrench experienced on the robots center of mass. More...
 
double calcKineticEnergy (Model &model, const Math::VectorNd &q, const Math::VectorNd &qdot, bool update_kinematics=true)
 Computes the kinetic energy of the full model. More...
 
double calcPotentialEnergy (Model &model, const Math::VectorNd &q, bool update_kinematics=true)
 Computes the potential energy of the full model. More...
 
Math::Vector3d calcSubtreeCenterOfMassScaledByMass (Model &model, const unsigned int bodyId, const Math::VectorNd &q, bool updateKinematics=true)
 Calculates the center of mass of a subtree starting with the body with ID bodyId and scales it by the total mass of the subtree. More...
 
double calcSubtreeMass (Model &model, const unsigned int bodyId)
 Calculates the total mass of the subtree beginning with body bodyId and traversing outwards from there. More...
 
std::string getBodyName (const RobotDynamics::Model &model, unsigned int body_id)
 get body name, returns empty string if bodyid is virtual and has multiple child bodies More...
 
std::string getDofName (const Math::SpatialVector &joint_dof)
 get string abbreviation for dof name from spatial vector. More...
 
std::string getModelDOFOverview (const Model &model)
 Creates a human readable overview of the Degrees of Freedom. More...
 
std::string getModelHierarchy (const Model &model)
 Creates a human readable overview of the model. More...
 
std::string getNamedBodyOriginsOverview (Model &model)
 Creates a human readable overview of the locations of all bodies that have names. More...
 
std::string printHierarchy (const RobotDynamics::Model &model, unsigned int body_index=0, int indent=0)
 
RobotDynamics::Math::FramePoint updateCenterOfMassFrame (Model &model, const Math::VectorNd &q, bool update_kinematics=true)
 Computes the center of mass and updates the center of mass reference frame of the model. More...
 
RobotDynamics::Math::FramePoint updateCenterOfMassFrame (Model &model, const Math::VectorNd &q, const Math::Vector3d &euler_ypr, bool update_kinematics=true)
 Computes the center of mass and updates the center of mass reference frame of the model. More...
 
RobotDynamics::Math::FramePoint updateCenterOfMassFrame (Model &model, const Math::VectorNd &q, const Math::Quaternion &orientation, bool update_kinematics=true)
 Computes the center of mass and updates the center of mass reference frame of the model. More...
 
void updateCenterOfMassFrame (Model &model, const Math::Vector3d &p_com)
 Updates the center of mass frame of the robot be at location p_com, aligned with world frame. More...
 
void updateCenterOfMassFrame (Model &model, const Math::Vector3d &p_com, const Math::Vector3d &euler_ypr)
 Updates the center of mass frame of the robot be at location p_com and to have orientation defined by the yaw/pitch/roll angles in euler_ypr argument. The euler_ypr argument is optional and if not provided the center of mass reference frame will be aligned with world. More...
 
void updateCenterOfMassFrame (Model &model, const Math::Vector3d &p_com, const Math::Quaternion &orientation)
 Updates the center of mass frame of the robot be at location p_com and to have orientation defined by the orientation argument. The quaternion argument is optional and if not provided the center of mass reference frame will be aligned with world. More...
 

Detailed Description

Namespace that contains optional helper functions.

Function Documentation

std::string RobotDynamics::Utils::printHierarchy ( const RobotDynamics::Model model,
unsigned int  body_index = 0,
int  indent = 0 
)

Definition at line 100 of file rdl_utils.cc.



rdl_dynamics
Author(s):
autogenerated on Tue Apr 20 2021 02:25:28