Tetrapod Project
Kinematics Class Reference

A class for analytical Kinematics Solving. More...

#include <kinematics.h>

Public Types

enum  LegType {
  frontLeft = 1 , frontRight = 2 , rearLeft = 3 , rearRight = 4 ,
  NONE
}
 Leg type enumerator. More...
 
enum  BodyType {
  base = 1 , hip = 2 , thigh = 3 , leg = 4 ,
  foot = 5
}
 Body type enumerator. More...
 

Public Member Functions

 Kinematics ()
 Constructor. More...
 
virtual ~Kinematics ()
 Destructor. More...
 
bool SolveForwardKinematics (const GeneralizedCoordinates &_q, FootstepPositions &_f_pos)
 The SolveForwardKinematics function calculates the Forward Kinematics, i.e. maps joint angles in Joint Space to a coordinate point in Coordinate Space. More...
 
bool SolveInverseKinematics (const Twist &_q_b, const FootstepPositions &_f_pos, JointSpaceVector &_q_r)
 The SolveInverseKinematics function calculates the Inverse Kinematics, i.e. maps a coordinate point in the Coordinate Space to joint angles in the Joint Space. More...
 
Vector3d SolveSingleLegForwardKinematics (const Vector3d &_h_pos, const double &_theta_hy, const double &_theta_hp, const double &_theta_kp)
 The SolveSingleLegForwardKinematics function calculates the Forward Kinematics for a single leg. More...
 
Vector3d SolveSingleLegForwardKinematics (const Vector3d &_joint_angles)
 The SolveSingleLegForwardKinematics function calculates the foot position in the hip frame. More...
 
Vector3d SolveSingleLegForwardKinematics (const LegType &_leg_type, const Vector3d &_joint_angles)
 The SolveSingleLegForwardKinematics function calculates the foot position in the hip frame. More...
 
Vector3d SolveSingleLegHipToFootForwardKinematics (const LegType &_leg_type, const Vector3d &_joint_angles)
 The SolveSingleLegHipToFootForwardKinematics function calculates the foot position in the hip frame. More...
 
bool SolveSingleLegInverseKinematics (const bool &_offset, const Vector3d &_h_pos, const Vector3d &_f_pos, Vector3d &_joint_angles)
 The SolveSingeLegInverseKinematics function calculates the inverse kinematics for a single leg. More...
 
bool SolveSingleLegInverseKinematics (const bool &_offset, const Vector3d &_f_pos, Vector3d &_joint_angles)
 The SolveSingeLegInverseKinematics function calculates the inverse kinematics of foot in the hip frame. More...
 
TransMatrix GetDhTransform (const double &_a, const double &_alpha, const double &_d, const double &_theta)
 The GetDhTransform function returns the Denavit-Hartenberg transformation from frame A to frame B. More...
 
TransMatrix GetHipToBodyTransform (const LegType &_leg, const BodyType &_body, const double &_theta_hy, const double &_theta_hp, const double &_theta_kp)
 The GetHipToBodyTransform function returns the homogeneous transformation from the hip frame to the specified body frame. More...
 
Eigen::Matrix< double, 3, 3 > GetRotationMatrixWToB (const double &_roll, const double &_pitch, const double &_yaw)
 The GetRotationMatrixWToB function returns the Euler Angles ZYX rotation matrix from World to Body frame, i.e., the transform from Body to World. More...
 
Eigen::Matrix< double, 3, 3 > GetRotationMatrixWToBDiff (const double &_roll, const double &_pitch, const double &_yaw, const double &_roll_rate, const double &_pitch_rate, const double &_yaw_rate)
 The GetRotationMatrixWToBDiff function returns the time derivative of the Euler Angles ZYX rotation matrix from World to Body frame. More...
 
Eigen::Matrix< double, 3, 3 > GetRotationMatrixWToC (const double &_roll, const double &_pitch, const double &_yaw)
 The GetRotationMatrixWToC function returns the Euler Angles ZYX rotation matrix from World to Control frame, i.e., the transform from Control to World. For flat-terrain the roll and pitch angles should be set to zero. More...
 
Eigen::Matrix< double, 3, 3 > GetRotationMatrixWToCDiff (const double &_roll, const double &_pitch, const double &_yaw, const double &_roll_rate, const double &_pitch_rate, const double &_yaw_rate)
 The GetRotationMatrixWToCDiff function returns the time derivative of the Euler Angles ZYX rotation matrix from World to Control frame. More...
 
Eigen::Matrix< double, 3, 3 > GetRotationMatrixCToB (const double &_roll, const double &_pitch, const double &_yaw)
 The GetRotationMatrixCToB function returns the Euler Angles ZYX rotation matrix from Control to Body frame, i.e., the transform from Body to Control. For flat-terrain the yaw angle should be set zero. More...
 
Eigen::Matrix< double, 3, 3 > GetRotationMatrixCToBDiff (const double &_roll, const double &_pitch, const double &_yaw, const double &_roll_rate, const double &_pitch_rate, const double &_yaw_rate)
 The GetRotationMatrixCToBDiff function returns the time derivative of the Euler Angles ZYX rotation matrix from World to Body frame. More...
 
Eigen::Matrix< double, 3, 1 > GetPositionBaseToBodyInB (const LegType &_leg, const BodyType &_body, const Eigen::Matrix< double, 18, 1 > &_q)
 The GetPositionBaseToBodyInB returns the position vector from base origin to COM position in body-frame for a given body. More...
 
Eigen::Matrix< double, 3, 3 > GetTranslationJacobianInB (const LegType &_leg, const BodyType &_body, const double &_theta_hy, const double &_theta_hp, const double &_theta_kp)
 The GetTranslationJacobianInB function returns the 3x3 Jacobian matrix for body linear velocities in the body(base)-frame for a given state. More...
 
Eigen::Matrix< double, 3, 12 > GetTranslationJacobianInB (const LegType &_leg, const BodyType &_body, const Eigen::Matrix< double, 12, 1 > &_q_r)
 The GetTranslationJacobianInB function returns the 3x12 Jacobian matrix for body linear velocities in the body(base)-frame for given states. More...
 
Eigen::Matrix< double, 3, 18 > GetTranslationJacobianInW (const LegType &_leg, const BodyType &_body, const Eigen::Matrix< double, 18, 1 > &_q)
 The GetTranslationJacobianInW function returns the 3x18 spatial translation Jacobian mapping generalized velocities to operational space twist of the body attached frame. More...
 
Eigen::Matrix< double, 3, 18 > GetTranslationJacobianInC (const LegType &_leg, const BodyType &_body, const Eigen::Matrix< double, 18, 1 > &_q)
 The GetTranslationJacobianInC function returns the 3x18 spatial translation Jacobian mapping generalized velocities to operational space twist of the control frame. More...
 
Eigen::Matrix< double, 3, 3 > GetTranslationJacobianInBDiff (const LegType &_leg, const BodyType &_body, const double &_theta_hy, const double &_theta_hp, const double &_theta_kp, const double &_dot_theta_hy, const double &_dot_theta_hp, const double &_dot_theta_kp)
 The GetTranslationJacobianDerivativeInB function returns the time derivative of the 3x3 translation Jacobian matrix. More...
 
Eigen::Matrix< double, 3, 12 > GetTranslationJacobianInBDiff (const LegType &_leg, const BodyType &_body, const Eigen::Matrix< double, 12, 1 > &_q_r, const Eigen::Matrix< double, 12, 1 > &_dot_q_r)
 The GetTranslationJacobianInBDiff function returns the time derivative of the 3x12 translation Jacobian matrix. More...
 
Eigen::Matrix< double, 3, 18 > GetTranslationJacobianInWDiff (const LegType &_leg, const BodyType &_body, const Eigen::Matrix< double, 18, 1 > &_q, const Eigen::Matrix< double, 18, 1 > &_u)
 The GetTranslationJacobianInWDiff function returns the time derivative of the 3x18 spatial translation Jacobian in the world frame. More...
 
Eigen::Matrix< double, 3, 18 > GetTranslationJacobianInCDiff (const LegType &_leg, const BodyType &_body, const Eigen::Matrix< double, 18, 1 > &_q, const Eigen::Matrix< double, 18, 1 > &_u)
 The GetTranslationJacobianInCDiff function returns the time derivative of the 3x18 spatial translation Jacobian in the control frame. More...
 
Eigen::Matrix< double, 3, 3 > GetRotationJacobianInB (const LegType &_leg, const BodyType &_body, const double &_theta_hy, const double &_theta_hp, const double &_theta_kp)
 The GetRotationJacobianInB function returns the 3x3 Jacobian matrix for body angular velocities in the body(base)-frame for a given state. More...
 
Eigen::Matrix< double, 3, 12 > GetRotationJacobianInB (const LegType &_leg, const BodyType &_body, const Eigen::Matrix< double, 12, 1 > &_q_r)
 The GetRotationJacobianInB function returns the 3x3 Jacobian matrix for body angular velocities in the body(base)-frame for a given state. More...
 
Eigen::Matrix< double, 3, 18 > GetRotationJacobianInW (const LegType &_leg, const BodyType &_body, const Eigen::Matrix< double, 18, 1 > &_q)
 The GetRotationJacobianInW function returns the 3x18 spatial rotation Jacobian mapping generalized velocities to operational space twist of the body attached frame. More...
 
Eigen::Matrix< double, 3, 18 > GetRotationJacobianInC (const LegType &_leg, const BodyType &_body, const Eigen::Matrix< double, 18, 1 > &_q)
 The GetRotationJacobianInC function returns the 3x18 spatial rotation Jacobian mapping generalized velocities to control frame twist of the body attached frame. More...
 
Eigen::Matrix< double, 3, 3 > GetRotationJacobianInBDiff (const LegType &_leg, const BodyType &_body, const double &_theta_hy, const double &_theta_hp, const double &_theta_kp, const double &_dot_theta_hy, const double &_dot_theta_hp, const double &_dot_theta_kp)
 The GetRotationJacobianInBDiff function returns the time derivative of the 3x3 Rotation Jacobian matrix. More...
 
Eigen::Matrix< double, 3, 12 > GetRotationJacobianInBDiff (const LegType &_leg, const BodyType &_body, const Eigen::Matrix< double, 12, 1 > &_q_r, const Eigen::Matrix< double, 12, 1 > &_dot_q_r)
 The GetRotationJacobianDerivativeInB function returns the time derivative of the 3x12 Rotation Jacobian matrix. More...
 
Eigen::Matrix< double, 3, 18 > GetRotationJacobianInWDiff (const LegType &_leg, const BodyType &_body, const Eigen::Matrix< double, 18, 1 > &_q, const Eigen::Matrix< double, 18, 1 > &_u)
 The GetRotationJacobianInWDiff function returns the time derivative of the 3x18 spatial Rotation Jacobian. More...
 
Eigen::Matrix< double, 3, 18 > GetRotationJacobianInCDiff (const LegType &_leg, const BodyType &_body, const Eigen::Matrix< double, 18, 1 > &_q, const Eigen::Matrix< double, 18, 1 > &_u)
 The GetRotationJacobianInCDiff function returns the time derivative of the 3x18 control frame Rotation Jacobian. More...
 
Eigen::Matrix< double, 6, 18 > GetJacobianInW (const LegType &_leg, const BodyType &_body, const Eigen::Matrix< double, 18, 1 > &_q)
 The GetJacobianInW function returns the 6x18 spatial Jacobian mapping generalized velocities to operational space twist of the body attached frame. More...
 
Eigen::Matrix< double, 6, 18 > GetJacobianInWDiff (const LegType &_leg, const BodyType &_body, const Eigen::Matrix< double, 18, 1 > &_q, const Eigen::Matrix< double, 18, 1 > &_u)
 The GetJacobianInW function returns the time derivative of the 6x18 spatial Jacobian. More...
 
Eigen::Matrix< double, Eigen::Dynamic, 18 > GetContactJacobianInW (std::vector< LegType > &_legs, const Eigen::Matrix< double, 18, 1 > &_q)
 The GetContactJacobianInW function returns the (3*n_c)x18 support Jacobian mapping reaction forces at the contact points to generalized coordinate space. More...
 
Eigen::Matrix< double, Eigen::Dynamic, 18 > GetContactJacobianInWDiff (std::vector< LegType > &_legs, const Eigen::Matrix< double, 18, 1 > &_q, const Eigen::Matrix< double, 18, 1 > &_u)
 The GetContactJacobianInWDiff function returns the time derivative of the (3*n_c)x18 support Jacobian. More...
 
Eigen::Matrix< double, Eigen::Dynamic, 18 > GetSwingJacobianInW (std::vector< LegType > &_legs, const Eigen::Matrix< double, 18, 1 > &_q)
 The GetSwingJacobianInW function returns the (3*n_s)x18 support Jacobian mapping swing foot velocities to generalized coordinate space. (n_s = 4 - n_c) More...
 
Eigen::Matrix< double, Eigen::Dynamic, 18 > GetSwingJacobianInWDiff (std::vector< LegType > &_legs, const Eigen::Matrix< double, 18, 1 > &_q, const Eigen::Matrix< double, 18, 1 > &_u)
 The GetContactJacobianInWDiff function returns the time derivative of the (3*n_s)x18 support Jacobian. (n_s = 4 - n_c) More...
 
Eigen::Matrix< double, 18, 18 > GetSingleBodyMassMatrix (const LegType &_leg, const BodyType &_body, const Eigen::Matrix< double, 18, 1 > &_q)
 The GetSingleBodyMassMatrix function returns the mass matrix for a single body in the system. More...
 
Eigen::Matrix< double, 18, 18 > GetMassMatrix (const Eigen::Matrix< double, 18, 1 > &_q)
 The GetMassMatrix function returns the mass matrix for the floating base system. More...
 
Eigen::Matrix< double, 3, 3 > GetSingleLegMassMatrix (const Eigen::Matrix< double, 3, 1 > &_q)
 
Eigen::Matrix< double, 18, 1 > GetSingleBodyCoriolisAndCentrifugalTerms (const LegType &_leg, const BodyType &_body, const Eigen::Matrix< double, 18, 1 > &_q, const Eigen::Matrix< double, 18, 1 > &_u)
 The GetSingleBodyCoriolisAndCentrifugalTerms function returns the coriolis and centrifugal terms for a single body in the system. More...
 
Eigen::Matrix< double, 18, 1 > GetCoriolisAndCentrifugalTerms (const Eigen::Matrix< double, 18, 1 > &_q, const Eigen::Matrix< double, 18, 1 > &_u)
 The GetCoriolisAndCentrifugalTerms function returns the coriolis and centrifugal terms for the floating base system. More...
 
Eigen::Matrix< double, 3, 1 > GetSingleLegCoriolisAndCentrifugalTerms (const Eigen::Matrix< double, 3, 1 > &_q, const Eigen::Matrix< double, 3, 1 > &_u)
 
Eigen::Matrix< double, 18, 1 > GetSingleBodyGravitationalTerms (const LegType &_leg, const BodyType &_body, const Eigen::Matrix< double, 18, 1 > &_q)
 The GetSingleBodyGravitationalTerms function returns the gravitational terms for a single body in the system. More...
 
Eigen::Matrix< double, 18, 1 > GetGravitationalTerms (const Eigen::Matrix< double, 18, 1 > &_q)
 The GetGravitationalTerms function returns the gravitational terms for the floating base system. More...
 
Eigen::Matrix< double, 3, 1 > GetSingleLegGravitationalTerms (const Eigen::Matrix< double, 3, 1 > &_q)
 
bool ValidateSolution (const JointSpaceVector &_q_r)
 The ValidateSolution function evaluates whether a set of joint angles is within joint limits. More...
 
bool ValidateSolution (const Eigen::Matrix< double, 3, 1 > &_q_r)
 Overloaded version of the ValidateSolution function, which evaluates whether a set of joint angles for a single leg is within the joint limits. More...
 
bool GetflOffset ()
 
bool GetfrOffset ()
 
bool GetrlOffset ()
 
bool GetrrOffset ()
 
Eigen::Matrix< double, 3, 1 > GetDistanceFromBaseToFrontLeftHipInB ()
 
Eigen::Matrix< double, 3, 1 > GetDistanceFromBaseToFrontRightHipInB ()
 
Eigen::Matrix< double, 3, 1 > GetDistanceFromBaseToRearLeftHipInB ()
 
Eigen::Matrix< double, 3, 1 > GetDistanceFromBaseToRearRightHipInB ()
 

Private Member Functions

Eigen::Matrix< double, 3, 3 > GetInertiaMatrix (const double &_I_XX, const double &_I_YY, const double &_I_ZZ, const double &_I_XY, const double &_I_XZ, const double &_I_YZ)
 The GetInertiaMatrix function returns the inertia matrix from the six inertial parameters. More...
 
double GetBodyMass (BodyType _body)
 
Eigen::Matrix< double, 3, 3 > GetBodyInertia (BodyType _body)
 
Eigen::Matrix< double, 3, 3 > GetBodyInertia (BodyType _body, LegType _leg)
 

Private Attributes

JointSpaceVector min_angles
 Minimum joint limits. More...
 
JointSpaceVector max_angles
 Maximum joint limits. More...
 
Vector3d positionBaseToFrontLeftInB
 Position vector relating the base coordinates to the front left hip. More...
 
Vector3d positionBaseToFrontRightInB
 Position vector relating the base coordinates to the front right hip. More...
 
Vector3d positionBaseToRearLeftInB
 Position vector relating the base coordinates to the rear left hip. More...
 
Vector3d positionBaseToRearRightInB
 Position vector relating the base coordinates to the rear right hip. More...
 
double L1
 Hip link length. More...
 
double L2
 Thigh (Femur) link length. More...
 
double L3
 Leg (Fibula & Tibia) link length. More...
 
double LC1
 Hip yaw joint to hip CoM length. More...
 
double LC2
 Hip pitch joint to thigh CoM length. More...
 
double LC3
 Knee pitch joint to leg CoM length. More...
 
bool flOffset
 Front Left offset. More...
 
bool frOffset
 Front Right offset. More...
 
bool rlOffset
 Rear Left offset. More...
 
bool rrOffset
 Rear Right offset. More...
 
double M0
 Body link mass. More...
 
double M1
 Hip link mass. More...
 
double M2
 Thigh link mass. More...
 
double M3
 Leg link mass. More...
 
Eigen::Matrix< double, 3, 3 > I0
 Body link inertia matrix. More...
 
Eigen::Matrix< double, 3, 3 > I1_fl_rr
 Front Left & Rear Right Hip link inertia matrix. More...
 
Eigen::Matrix< double, 3, 3 > I1_fr_rl
 Front Right & Rear Left Hip link inertia matrix. More...
 
Eigen::Matrix< double, 3, 3 > I2
 Thigh link inertia matrix. More...
 
Eigen::Matrix< double, 3, 3 > I3
 Leg link inertia matrix. More...
 

Detailed Description

A class for analytical Kinematics Solving.

Definition at line 53 of file kinematics.h.

Member Enumeration Documentation

◆ LegType

Leg type enumerator.

Enumerator
frontLeft 
frontRight 
rearLeft 
rearRight 
NONE 

Definition at line 56 of file kinematics.h.

◆ BodyType

Body type enumerator.

Enumerator
base 
hip 
thigh 
leg 
foot 

Definition at line 59 of file kinematics.h.

Constructor & Destructor Documentation

◆ Kinematics()

Kinematics::Kinematics ( )

Constructor.

Definition at line 31 of file kinematics.cpp.

◆ ~Kinematics()

Kinematics::~Kinematics ( )
virtual

Destructor.

Definition at line 101 of file kinematics.cpp.

Member Function Documentation

◆ SolveForwardKinematics()

bool Kinematics::SolveForwardKinematics ( const GeneralizedCoordinates _q,
FootstepPositions _f_pos 
)

The SolveForwardKinematics function calculates the Forward Kinematics, i.e. maps joint angles in Joint Space to a coordinate point in Coordinate Space.

Parameters
[in]_qGeneralized coordinates. containing the floating base and joint positions.
[out]_f_posFootstep positions generated from solving the forward kinematics.
Returns
Evaluates true if an Forward Kinematics solution is found, and false if not.

Definition at line 165 of file kinematics.cpp.

◆ SolveInverseKinematics()

bool Kinematics::SolveInverseKinematics ( const Twist _q_b,
const FootstepPositions _f_pos,
JointSpaceVector _q_r 
)

The SolveInverseKinematics function calculates the Inverse Kinematics, i.e. maps a coordinate point in the Coordinate Space to joint angles in the Joint Space.

Parameters
[in]_q_bBase Pose in the world frame.
[in]_f_posFootstep positions in the world frame.
[out]_q_rJoint angles from the Inverse Kinematics solution.
Returns
Evaluates true if an Inverse Kinematics solution is found, and false if not.

Definition at line 104 of file kinematics.cpp.

◆ SolveSingleLegForwardKinematics() [1/3]

Vector3d Kinematics::SolveSingleLegForwardKinematics ( const Vector3d _h_pos,
const double &  _theta_hy,
const double &  _theta_hp,
const double &  _theta_kp 
)

The SolveSingleLegForwardKinematics function calculates the Forward Kinematics for a single leg.

Parameters
[in]_h_posHip position in world frame.
[in]_theta_hyHip yaw angle.
[in]_theta_hpHip pitch angle.
[in]_theta_kpKnee pitch angle.
Returns
Returns end-effector position in Coordinate Space.

Definition at line 229 of file kinematics.cpp.

◆ SolveSingleLegForwardKinematics() [2/3]

Vector3d Kinematics::SolveSingleLegForwardKinematics ( const Vector3d _joint_angles)

The SolveSingleLegForwardKinematics function calculates the foot position in the hip frame.

Parameters
[in]_joint_anglesA vector containing the hip yaw, hip pitch and knee pitch angles
Returns
Returns end-effector position in the hip frame.

Definition at line 289 of file kinematics.cpp.

◆ SolveSingleLegForwardKinematics() [3/3]

Vector3d Kinematics::SolveSingleLegForwardKinematics ( const LegType _leg_type,
const Vector3d _joint_angles 
)

The SolveSingleLegForwardKinematics function calculates the foot position in the hip frame.

Parameters
[in]_leg_typeIndicates which leg it is
[in]_joint_anglesA vector containing the hip yaw, hip pitch and knee pitch angles
Returns
Returns end-effector position in the hip frame.

Definition at line 248 of file kinematics.cpp.

◆ SolveSingleLegHipToFootForwardKinematics()

Eigen::Matrix< double, 3, 1 > Kinematics::SolveSingleLegHipToFootForwardKinematics ( const LegType _leg_type,
const Vector3d _joint_angles 
)

The SolveSingleLegHipToFootForwardKinematics function calculates the foot position in the hip frame.

Parameters
[in]_leg_typeIndicates which leg it is
[in]_joint_anglesA vector containing the hip yaw, hip pitch and knee pitch angles
Returns
Returns end-effector position in the hip frame.

Definition at line 262 of file kinematics.cpp.

◆ SolveSingleLegInverseKinematics() [1/2]

bool Kinematics::SolveSingleLegInverseKinematics ( const bool &  _offset,
const Vector3d _h_pos,
const Vector3d _f_pos,
Vector3d _joint_angles 
)

The SolveSingeLegInverseKinematics function calculates the inverse kinematics for a single leg.

Parameters
[in]_offsetBool indicating whether the leg is roll offset to -90 or 90 degrees. True indicates roll offset of of 90 deg, false indicates roll offset of -90 degrees.
[in]_h_posHip position in world frame.
[in]_f_posFoot position in world frame.
[out]_joint_anglesJoint angles from the Inverse Kinematics solution for a single-leg (sl).
Returns
Evaluates true if an Inverse Kinematics solution is found, and false if not.

Definition at line 296 of file kinematics.cpp.

◆ SolveSingleLegInverseKinematics() [2/2]

bool Kinematics::SolveSingleLegInverseKinematics ( const bool &  _offset,
const Vector3d _f_pos,
Vector3d _joint_angles 
)

The SolveSingeLegInverseKinematics function calculates the inverse kinematics of foot in the hip frame.

Parameters
[in]_offsetBool indicating whether the leg is roll offset to -90 or 90 degrees. True indicates roll offset of of 90 deg, false indicates roll offset of -90 degrees.
[in]_f_posFoot position in hip frame.
[out]_joint_anglesJoint angles from the Inverse Kinematics solution for a single-leg (sl).
Returns
Evaluates true if an Inverse Kinematics solution is found, and false if not.

Definition at line 362 of file kinematics.cpp.

◆ GetDhTransform()

TransMatrix Kinematics::GetDhTransform ( const double &  _a,
const double &  _alpha,
const double &  _d,
const double &  _theta 
)

The GetDhTransform function returns the Denavit-Hartenberg transformation from frame A to frame B.

Parameters
[in]_aLink length.
[in]_alphaLink twist.
[in]_dLink offset.
[in]_thetaJoint angle.
Returns
Returns the kindr homogeneous transformation matrix from frame A to frame B.

Definition at line 369 of file kinematics.cpp.

◆ GetHipToBodyTransform()

TransMatrix Kinematics::GetHipToBodyTransform ( const LegType _leg,
const BodyType _body,
const double &  _theta_hy,
const double &  _theta_hp,
const double &  _theta_kp 
)

The GetHipToBodyTransform function returns the homogeneous transformation from the hip frame to the specified body frame.

Parameters
[in]_legLeg type.
[in]_bodyBody type.
[in]_theta_hyHip yaw angle.
[in]_theta_hpHip pitch angle.
[in]_theta_kpKnee pitch angle.
Returns
Returns the kindr homogeneous transformation matrix from hip to body.

Definition at line 389 of file kinematics.cpp.

◆ GetRotationMatrixWToB()

Eigen::Matrix< double, 3, 3 > Kinematics::GetRotationMatrixWToB ( const double &  _roll,
const double &  _pitch,
const double &  _yaw 
)

The GetRotationMatrixWToB function returns the Euler Angles ZYX rotation matrix from World to Body frame, i.e., the transform from Body to World.

Parameters
[in]_rollRoll angle (x-axis).
[in]_pitchPitch angle (y-axis).
[in]_yawYaw angle (z-axis).
Returns
Returns the rotation matrix from World to Body frame (transform from Body to World), using the Euler Angles ZYX convention.

Definition at line 539 of file kinematics.cpp.

◆ GetRotationMatrixWToBDiff()

Eigen::Matrix< double, 3, 3 > Kinematics::GetRotationMatrixWToBDiff ( const double &  _roll,
const double &  _pitch,
const double &  _yaw,
const double &  _roll_rate,
const double &  _pitch_rate,
const double &  _yaw_rate 
)

The GetRotationMatrixWToBDiff function returns the time derivative of the Euler Angles ZYX rotation matrix from World to Body frame.

Parameters
[in]_rollRoll angle (x-axis).
[in]_pitchPitch angle (y-axis).
[in]_yawYaw angle (z-axis).
[in]_roll_rateRoll rate (x-axis).
[in]_pitch_ratePitch rate (y-axis).
[in]_yaw_rateYaw rate (z-axis).
Returns
Returns the time derivative of the rotation matrix from World to Body frame, using the Euler Angles ZYX convention.

Definition at line 552 of file kinematics.cpp.

◆ GetRotationMatrixWToC()

Eigen::Matrix< double, 3, 3 > Kinematics::GetRotationMatrixWToC ( const double &  _roll,
const double &  _pitch,
const double &  _yaw 
)

The GetRotationMatrixWToC function returns the Euler Angles ZYX rotation matrix from World to Control frame, i.e., the transform from Control to World. For flat-terrain the roll and pitch angles should be set to zero.

Parameters
[in]_rollRoll angle (x-axis).
[in]_pitchPitch angle (y-axis).
[in]_yawYaw angle (z-axis).
Returns
Returns the rotation matrix from World to Control frame (transform from Body to World), using the Euler Angles ZYX convention.

Definition at line 574 of file kinematics.cpp.

◆ GetRotationMatrixWToCDiff()

Eigen::Matrix< double, 3, 3 > Kinematics::GetRotationMatrixWToCDiff ( const double &  _roll,
const double &  _pitch,
const double &  _yaw,
const double &  _roll_rate,
const double &  _pitch_rate,
const double &  _yaw_rate 
)

The GetRotationMatrixWToCDiff function returns the time derivative of the Euler Angles ZYX rotation matrix from World to Control frame.

Parameters
[in]_rollRoll angle (x-axis).
[in]_pitchPitch angle (y-axis).
[in]_yawYaw angle (z-axis).
[in]_roll_rateRoll rate (x-axis).
[in]_pitch_ratePitch rate (y-axis).
[in]_yaw_rateYaw rate (z-axis).
Returns
Returns the time derivative of the rotation matrix from World to Control frame, using the Euler Angles ZYX convention.

Definition at line 587 of file kinematics.cpp.

◆ GetRotationMatrixCToB()

Eigen::Matrix< double, 3, 3 > Kinematics::GetRotationMatrixCToB ( const double &  _roll,
const double &  _pitch,
const double &  _yaw 
)

The GetRotationMatrixCToB function returns the Euler Angles ZYX rotation matrix from Control to Body frame, i.e., the transform from Body to Control. For flat-terrain the yaw angle should be set zero.

Parameters
[in]_rollRoll angle (x-axis).
[in]_pitchPitch angle (y-axis).
[in]_yawYaw angle (z-axis).
Returns
Returns the rotation matrix from Control to Body frame (transform from Body to Control), using the Euler Angles ZYX convention.

Definition at line 609 of file kinematics.cpp.

◆ GetRotationMatrixCToBDiff()

Eigen::Matrix< double, 3, 3 > Kinematics::GetRotationMatrixCToBDiff ( const double &  _roll,
const double &  _pitch,
const double &  _yaw,
const double &  _roll_rate,
const double &  _pitch_rate,
const double &  _yaw_rate 
)

The GetRotationMatrixCToBDiff function returns the time derivative of the Euler Angles ZYX rotation matrix from World to Body frame.

Parameters
[in]_rollRoll angle (x-axis).
[in]_pitchPitch angle (y-axis).
[in]_yawYaw angle (z-axis).
[in]_roll_rateRoll rate (x-axis).
[in]_pitch_ratePitch rate (y-axis).
[in]_yaw_rateYaw rate (z-axis).
Returns
Returns the time derivative of the rotation matrix from Control to Body frame, using the Euler Angles ZYX convention.

Definition at line 622 of file kinematics.cpp.

◆ GetPositionBaseToBodyInB()

Eigen::Matrix< double, 3, 1 > Kinematics::GetPositionBaseToBodyInB ( const LegType _leg,
const BodyType _body,
const Eigen::Matrix< double, 18, 1 > &  _q 
)

The GetPositionBaseToBodyInB returns the position vector from base origin to COM position in body-frame for a given body.

Parameters
[in]_legLeg type.
[in]_bodyBody type.
[in]_qGeneralized coordinates.
Returns
Returns the position vector from base to foot.

Definition at line 644 of file kinematics.cpp.

◆ GetTranslationJacobianInB() [1/2]

Eigen::Matrix< double, 3, 3 > Kinematics::GetTranslationJacobianInB ( const LegType _leg,
const BodyType _body,
const double &  _theta_hy,
const double &  _theta_hp,
const double &  _theta_kp 
)

The GetTranslationJacobianInB function returns the 3x3 Jacobian matrix for body linear velocities in the body(base)-frame for a given state.

Parameters
[in]_legLeg type.
[in]_bodyBody type.
[in]_theta_hyHip yaw angle.
[in]_theta_hpHip pitch angle.
[in]_theta_kpKnee pitch angle.
Returns
Returns the 3x3 translation Jacobian Matrix relating body linear velocities to joint velocities.

Definition at line 723 of file kinematics.cpp.

◆ GetTranslationJacobianInB() [2/2]

Eigen::Matrix< double, 3, 12 > Kinematics::GetTranslationJacobianInB ( const LegType _leg,
const BodyType _body,
const Eigen::Matrix< double, 12, 1 > &  _q_r 
)

The GetTranslationJacobianInB function returns the 3x12 Jacobian matrix for body linear velocities in the body(base)-frame for given states.

Parameters
[in]_legLeg type.
[in]_bodyBody type.
[in]_q_rJoint coordinates.
Returns
Returns the 3x12 translation Jacobian Matrix relating body linear velocities to joint velocities.

Definition at line 840 of file kinematics.cpp.

◆ GetTranslationJacobianInW()

Eigen::Matrix< double, 3, 18 > Kinematics::GetTranslationJacobianInW ( const LegType _leg,
const BodyType _body,
const Eigen::Matrix< double, 18, 1 > &  _q 
)

The GetTranslationJacobianInW function returns the 3x18 spatial translation Jacobian mapping generalized velocities to operational space twist of the body attached frame.

Parameters
[in]_legLeg type.
[in]_bodyBody type.
[in]_qGeneralized coordinates.
Returns
Returns the translation Jacobian Matrix mapping from generalized velocities to the operational space (world-frame) twist of the body attached frame.

Definition at line 911 of file kinematics.cpp.

◆ GetTranslationJacobianInC()

Eigen::Matrix< double, 3, 18 > Kinematics::GetTranslationJacobianInC ( const LegType _leg,
const BodyType _body,
const Eigen::Matrix< double, 18, 1 > &  _q 
)

The GetTranslationJacobianInC function returns the 3x18 spatial translation Jacobian mapping generalized velocities to operational space twist of the control frame.

Parameters
[in]_legLeg type.
[in]_bodyBody type.
[in]_qGeneralized coordinates.
Returns
Returns the translation Jacobian Matrix mapping from generalized velocities to the operational space (world-frame) twist of the control frame.

Definition at line 969 of file kinematics.cpp.

◆ GetTranslationJacobianInBDiff() [1/2]

Eigen::Matrix< double, 3, 3 > Kinematics::GetTranslationJacobianInBDiff ( const LegType _leg,
const BodyType _body,
const double &  _theta_hy,
const double &  _theta_hp,
const double &  _theta_kp,
const double &  _dot_theta_hy,
const double &  _dot_theta_hp,
const double &  _dot_theta_kp 
)

The GetTranslationJacobianDerivativeInB function returns the time derivative of the 3x3 translation Jacobian matrix.

Parameters
[in]_legLeg type.
[in]_bodyBody type.
[in]_theta_hyHip yaw angle.
[in]_theta_hpHip pitch angle.
[in]_theta_kpKnee pitch angle.
[in]_dot_theta_hyHip yaw rate.
[in]_dot_theta_hpHip pitch rate.
[in]_dot_theta_kpKnee pitch rate.
Returns
Returns the 3x3 time derivative of the translation Jacobian Matrix.

Definition at line 1027 of file kinematics.cpp.

◆ GetTranslationJacobianInBDiff() [2/2]

Eigen::Matrix< double, 3, 12 > Kinematics::GetTranslationJacobianInBDiff ( const LegType _leg,
const BodyType _body,
const Eigen::Matrix< double, 12, 1 > &  _q_r,
const Eigen::Matrix< double, 12, 1 > &  _dot_q_r 
)

The GetTranslationJacobianInBDiff function returns the time derivative of the 3x12 translation Jacobian matrix.

Parameters
[in]_legLeg type.
[in]_bodyBody type.
[in]_q_rJoint coordinates.
[in]_dot_q_rJoint velocities.
Returns
Returns the 3x12 time derivative of the translation Jacobian Matrix.

Definition at line 1159 of file kinematics.cpp.

◆ GetTranslationJacobianInWDiff()

Eigen::Matrix< double, 3, 18 > Kinematics::GetTranslationJacobianInWDiff ( const LegType _leg,
const BodyType _body,
const Eigen::Matrix< double, 18, 1 > &  _q,
const Eigen::Matrix< double, 18, 1 > &  _u 
)

The GetTranslationJacobianInWDiff function returns the time derivative of the 3x18 spatial translation Jacobian in the world frame.

Parameters
[in]_legLeg type.
[in]_bodyBody type.
[in]_qGeneralized coordinates.
[in]_uGeneralized velocities.
Returns
Returns the 3x18 time derivative of the translation Jacobian Matrix in the world frame.

Definition at line 1254 of file kinematics.cpp.

◆ GetTranslationJacobianInCDiff()

Eigen::Matrix< double, 3, 18 > Kinematics::GetTranslationJacobianInCDiff ( const LegType _leg,
const BodyType _body,
const Eigen::Matrix< double, 18, 1 > &  _q,
const Eigen::Matrix< double, 18, 1 > &  _u 
)

The GetTranslationJacobianInCDiff function returns the time derivative of the 3x18 spatial translation Jacobian in the control frame.

Parameters
[in]_legLeg type.
[in]_bodyBody type.
[in]_qGeneralized coordinates.
[in]_uGeneralized velocities.
Returns
Returns the 3x18 time derivative of the translation Jacobian Matrix in the control frame.

Definition at line 1337 of file kinematics.cpp.

◆ GetRotationJacobianInB() [1/2]

Eigen::Matrix< double, 3, 3 > Kinematics::GetRotationJacobianInB ( const LegType _leg,
const BodyType _body,
const double &  _theta_hy,
const double &  _theta_hp,
const double &  _theta_kp 
)

The GetRotationJacobianInB function returns the 3x3 Jacobian matrix for body angular velocities in the body(base)-frame for a given state.

Parameters
[in]_legLeg type.
[in]_bodyBody type.
[in]_theta_hyHip yaw angle.
[in]_theta_hpHip pitch angle.
[in]_theta_kpKnee pitch angle.
Returns
Returns the 3x3 rotation Jacobian Matrix relating body angular velocities to joint velocities.

Definition at line 1420 of file kinematics.cpp.

◆ GetRotationJacobianInB() [2/2]

Eigen::Matrix< double, 3, 12 > Kinematics::GetRotationJacobianInB ( const LegType _leg,
const BodyType _body,
const Eigen::Matrix< double, 12, 1 > &  _q_r 
)

The GetRotationJacobianInB function returns the 3x3 Jacobian matrix for body angular velocities in the body(base)-frame for a given state.

Parameters
[in]_legLeg type.
[in]_bodyBody type.
[in]_q_rJoint coordinates.
Returns
Returns the 3x12 rotation Jacobian Matrix relating body angular velocities to joint velocities.

Definition at line 1540 of file kinematics.cpp.

◆ GetRotationJacobianInW()

Eigen::Matrix< double, 3, 18 > Kinematics::GetRotationJacobianInW ( const LegType _leg,
const BodyType _body,
const Eigen::Matrix< double, 18, 1 > &  _q 
)

The GetRotationJacobianInW function returns the 3x18 spatial rotation Jacobian mapping generalized velocities to operational space twist of the body attached frame.

Parameters
[in]_legLeg type.
[in]_bodyBody type.
[in]_qGeneralized coordinates.
Returns
Returns the rotation Jacobian Matrix mapping from generalized velocities to the operational space (world-frame) twist of the body attached frame.

Definition at line 1611 of file kinematics.cpp.

◆ GetRotationJacobianInC()

Eigen::Matrix< double, 3, 18 > Kinematics::GetRotationJacobianInC ( const LegType _leg,
const BodyType _body,
const Eigen::Matrix< double, 18, 1 > &  _q 
)

The GetRotationJacobianInC function returns the 3x18 spatial rotation Jacobian mapping generalized velocities to control frame twist of the body attached frame.

Parameters
[in]_legLeg type.
[in]_bodyBody type.
[in]_qGeneralized coordinates.
Returns
Returns the rotation Jacobian Matrix mapping from generalized velocities to the control frame twist of the body attached frame.

Definition at line 1661 of file kinematics.cpp.

◆ GetRotationJacobianInBDiff() [1/2]

Eigen::Matrix< double, 3, 3 > Kinematics::GetRotationJacobianInBDiff ( const LegType _leg,
const BodyType _body,
const double &  _theta_hy,
const double &  _theta_hp,
const double &  _theta_kp,
const double &  _dot_theta_hy,
const double &  _dot_theta_hp,
const double &  _dot_theta_kp 
)

The GetRotationJacobianInBDiff function returns the time derivative of the 3x3 Rotation Jacobian matrix.

Parameters
[in]_legLeg type.
[in]_bodyBody type.
[in]_theta_hyHip yaw angle.
[in]_theta_hpHip pitch angle.
[in]_theta_kpKnee pitch angle.
[in]_dot_theta_hyHip yaw rate.
[in]_dot_theta_hpHip pitch rate.
[in]_dot_theta_kpKnee pitch rate.
Returns
Returns the 3x3 time derivative of the Rotation Jacobian Matrix.

Definition at line 1711 of file kinematics.cpp.

◆ GetRotationJacobianInBDiff() [2/2]

Eigen::Matrix< double, 3, 12 > Kinematics::GetRotationJacobianInBDiff ( const LegType _leg,
const BodyType _body,
const Eigen::Matrix< double, 12, 1 > &  _q_r,
const Eigen::Matrix< double, 12, 1 > &  _dot_q_r 
)

The GetRotationJacobianDerivativeInB function returns the time derivative of the 3x12 Rotation Jacobian matrix.

Parameters
[in]_legLeg type.
[in]_bodyBody type.
[in]_q_rJoint coordinates.
[in]_dot_q_rJoint velocities.
Returns
Returns the 3x12 time derivative of the Rotation Jacobian Matrix.

Definition at line 1822 of file kinematics.cpp.

◆ GetRotationJacobianInWDiff()

Eigen::Matrix< double, 3, 18 > Kinematics::GetRotationJacobianInWDiff ( const LegType _leg,
const BodyType _body,
const Eigen::Matrix< double, 18, 1 > &  _q,
const Eigen::Matrix< double, 18, 1 > &  _u 
)

The GetRotationJacobianInWDiff function returns the time derivative of the 3x18 spatial Rotation Jacobian.

Parameters
[in]_legLeg type.
[in]_bodyBody type.
[in]_qGeneralized coordinates.
[in]_uGeneralized velocities.
Returns
Returns the 3x18 time derivative of the Rotation Jacobian Matrix in the world frame.

Definition at line 1917 of file kinematics.cpp.

◆ GetRotationJacobianInCDiff()

Eigen::Matrix< double, 3, 18 > Kinematics::GetRotationJacobianInCDiff ( const LegType _leg,
const BodyType _body,
const Eigen::Matrix< double, 18, 1 > &  _q,
const Eigen::Matrix< double, 18, 1 > &  _u 
)

The GetRotationJacobianInCDiff function returns the time derivative of the 3x18 control frame Rotation Jacobian.

Parameters
[in]_legLeg type.
[in]_bodyBody type.
[in]_qGeneralized coordinates.
[in]_uGeneralized velocities.
Returns
Returns the 3x18 time derivative of the Rotation Jacobian Matrix in the control frame.

Definition at line 1991 of file kinematics.cpp.

◆ GetJacobianInW()

Eigen::Matrix< double, 6, 18 > Kinematics::GetJacobianInW ( const LegType _leg,
const BodyType _body,
const Eigen::Matrix< double, 18, 1 > &  _q 
)

The GetJacobianInW function returns the 6x18 spatial Jacobian mapping generalized velocities to operational space twist of the body attached frame.

Parameters
[in]_legLeg type.
[in]_qGeneralized coordinates.
Returns
Returns the spatial Jacobian Matrix mapping from generalized velocities to the operational space (world-frame) twist of the body attached frame.

Definition at line 2065 of file kinematics.cpp.

◆ GetJacobianInWDiff()

Eigen::Matrix< double, 6, 18 > Kinematics::GetJacobianInWDiff ( const LegType _leg,
const BodyType _body,
const Eigen::Matrix< double, 18, 1 > &  _q,
const Eigen::Matrix< double, 18, 1 > &  _u 
)

The GetJacobianInW function returns the time derivative of the 6x18 spatial Jacobian.

Parameters
[in]_legLeg type.
[in]_qGeneralized coordinates.
[in]_uGeneralized velocities.
Returns
Returns the time derivative of the spatial Jacobian Matrix.

Definition at line 2083 of file kinematics.cpp.

◆ GetContactJacobianInW()

Eigen::Matrix< double, Eigen::Dynamic, 18 > Kinematics::GetContactJacobianInW ( std::vector< LegType > &  _legs,
const Eigen::Matrix< double, 18, 1 > &  _q 
)

The GetContactJacobianInW function returns the (3*n_c)x18 support Jacobian mapping reaction forces at the contact points to generalized coordinate space.

Parameters
[in]_legsA vector of leg types containing the contact points.
[in]_qGeneralized coordinates.
Returns
Returns the contact Jacobian Matrix mapping reaction (contact) forces to generalized coordinate space.

Definition at line 2104 of file kinematics.cpp.

◆ GetContactJacobianInWDiff()

Eigen::Matrix< double, Eigen::Dynamic, 18 > Kinematics::GetContactJacobianInWDiff ( std::vector< LegType > &  _legs,
const Eigen::Matrix< double, 18, 1 > &  _q,
const Eigen::Matrix< double, 18, 1 > &  _u 
)

The GetContactJacobianInWDiff function returns the time derivative of the (3*n_c)x18 support Jacobian.

Parameters
[in]_legsA vector of leg types containing the contact points.
[in]_qGeneralized coordinates.
[in]_uGeneralized velocities.
Returns
Returns the time derivative of the contact Jacobian Matrix.

Definition at line 2156 of file kinematics.cpp.

◆ GetSwingJacobianInW()

Eigen::Matrix< double, Eigen::Dynamic, 18 > Kinematics::GetSwingJacobianInW ( std::vector< LegType > &  _legs,
const Eigen::Matrix< double, 18, 1 > &  _q 
)

The GetSwingJacobianInW function returns the (3*n_s)x18 support Jacobian mapping swing foot velocities to generalized coordinate space. (n_s = 4 - n_c)

Parameters
[in]_legsA vector of leg types containing the swing legs.
[in]_qGeneralized coordinates.
Returns
Returns the support Jacobian Matrix mapping swing foot velocities to generalized coordinate space.

Definition at line 2210 of file kinematics.cpp.

◆ GetSwingJacobianInWDiff()

Eigen::Matrix< double, Eigen::Dynamic, 18 > Kinematics::GetSwingJacobianInWDiff ( std::vector< LegType > &  _legs,
const Eigen::Matrix< double, 18, 1 > &  _q,
const Eigen::Matrix< double, 18, 1 > &  _u 
)

The GetContactJacobianInWDiff function returns the time derivative of the (3*n_s)x18 support Jacobian. (n_s = 4 - n_c)

Parameters
[in]_legsA vector of leg types containing the swing legs.
[in]_qGeneralized coordinates.
[in]_uGeneralized velocities.
Returns
Returns the time derivative of the support swing-leg Jacobian Matrix.

Definition at line 2259 of file kinematics.cpp.

◆ GetSingleBodyMassMatrix()

Eigen::Matrix< double, 18, 18 > Kinematics::GetSingleBodyMassMatrix ( const LegType _leg,
const BodyType _body,
const Eigen::Matrix< double, 18, 1 > &  _q 
)

The GetSingleBodyMassMatrix function returns the mass matrix for a single body in the system.

Parameters
[in]_legLeg type.
[in]_bodyBody type.
[in]_qGeneralized coordinates.
Returns
Returns a single body mass matrix as specified by leg and body type.

Definition at line 2309 of file kinematics.cpp.

◆ GetMassMatrix()

Eigen::Matrix< double, 18, 18 > Kinematics::GetMassMatrix ( const Eigen::Matrix< double, 18, 1 > &  _q)

The GetMassMatrix function returns the mass matrix for the floating base system.

Parameters
[in]_qGeneralized coordinates.
Returns
Returns an orthogonal mass matrix (n_q x n_q) for the floating base system.

Definition at line 2330 of file kinematics.cpp.

◆ GetSingleLegMassMatrix()

Eigen::Matrix< double, 3, 3 > Kinematics::GetSingleLegMassMatrix ( const Eigen::Matrix< double, 3, 1 > &  _q)

Definition at line 2363 of file kinematics.cpp.

◆ GetSingleBodyCoriolisAndCentrifugalTerms()

Eigen::Matrix< double, 18, 1 > Kinematics::GetSingleBodyCoriolisAndCentrifugalTerms ( const LegType _leg,
const BodyType _body,
const Eigen::Matrix< double, 18, 1 > &  _q,
const Eigen::Matrix< double, 18, 1 > &  _u 
)

The GetSingleBodyCoriolisAndCentrifugalTerms function returns the coriolis and centrifugal terms for a single body in the system.

Parameters
[in]_legLeg type.
[in]_bodyBody type.
[in]_qGeneralized coordinates.
[in]_uGeneralized velocities.
Returns
Returns a single body coriolis and centrifugal terms as specified by leg and body type.

Definition at line 2386 of file kinematics.cpp.

◆ GetCoriolisAndCentrifugalTerms()

Eigen::Matrix< double, 18, 1 > Kinematics::GetCoriolisAndCentrifugalTerms ( const Eigen::Matrix< double, 18, 1 > &  _q,
const Eigen::Matrix< double, 18, 1 > &  _u 
)

The GetCoriolisAndCentrifugalTerms function returns the coriolis and centrifugal terms for the floating base system.

Parameters
[in]_qGeneralized coordinates.
[in]_uGeneralized velocities.
Returns
Returns coriolis and centrifugal terms for the floating base system.

Definition at line 2419 of file kinematics.cpp.

◆ GetSingleLegCoriolisAndCentrifugalTerms()

Eigen::Matrix< double, 3, 1 > Kinematics::GetSingleLegCoriolisAndCentrifugalTerms ( const Eigen::Matrix< double, 3, 1 > &  _q,
const Eigen::Matrix< double, 3, 1 > &  _u 
)

Definition at line 2453 of file kinematics.cpp.

◆ GetSingleBodyGravitationalTerms()

Eigen::Matrix< double, 18, 1 > Kinematics::GetSingleBodyGravitationalTerms ( const LegType _leg,
const BodyType _body,
const Eigen::Matrix< double, 18, 1 > &  _q 
)

The GetSingleBodyGravitationalTerms function returns the gravitational terms for a single body in the system.

Parameters
[in]_legLeg type.
[in]_bodyBody type.
[in]_qGeneralized coordinates.
Returns
Returns a single body gravitational terms as specified by leg and body type.

Definition at line 2488 of file kinematics.cpp.

◆ GetGravitationalTerms()

Eigen::Matrix< double, 18, 1 > Kinematics::GetGravitationalTerms ( const Eigen::Matrix< double, 18, 1 > &  _q)

The GetGravitationalTerms function returns the gravitational terms for the floating base system.

Parameters
[in]_qGeneralized coordinates.
Returns
Returns gravitational terms for the floating base system.

Definition at line 2543 of file kinematics.cpp.

◆ GetSingleLegGravitationalTerms()

Eigen::Matrix< double, 3, 1 > Kinematics::GetSingleLegGravitationalTerms ( const Eigen::Matrix< double, 3, 1 > &  _q)

Definition at line 2578 of file kinematics.cpp.

◆ ValidateSolution() [1/2]

bool Kinematics::ValidateSolution ( const JointSpaceVector _q_r)

The ValidateSolution function evaluates whether a set of joint angles is within joint limits.

Parameters
[in]_q_rJoint angles generated by the IK solver.
Returns
Evaluates true if IK solution is valid, and false if not.

Definition at line 2603 of file kinematics.cpp.

◆ ValidateSolution() [2/2]

bool Kinematics::ValidateSolution ( const Eigen::Matrix< double, 3, 1 > &  _q_r)

Overloaded version of the ValidateSolution function, which evaluates whether a set of joint angles for a single leg is within the joint limits.

Parameters
[in]_q_rJoint angles for a single leg generated by the IK solver.
Returns
Evaluates true if the IK solution is valid, and false if not.

Definition at line 2622 of file kinematics.cpp.

◆ GetInertiaMatrix()

Eigen::Matrix< double, 3, 3 > Kinematics::GetInertiaMatrix ( const double &  _I_XX,
const double &  _I_YY,
const double &  _I_ZZ,
const double &  _I_XY,
const double &  _I_XZ,
const double &  _I_YZ 
)
private

The GetInertiaMatrix function returns the inertia matrix from the six inertial parameters.

Parameters
[in]_I_XXinertia about the x axis
[in]_I_YYinertia about the y axis
[in]_I_ZZinertia about the z axis
[in]_I_XYinertia about the xy axis
[in]_I_XZinertia about the xz axis
[in]_I_YZinertia about the yz axis

Definition at line 2642 of file kinematics.cpp.

◆ GetBodyMass()

double Kinematics::GetBodyMass ( BodyType  _body)
private

Definition at line 2663 of file kinematics.cpp.

◆ GetBodyInertia() [1/2]

Eigen::Matrix< double, 3, 3 > Kinematics::GetBodyInertia ( BodyType  _body)
private

Definition at line 2705 of file kinematics.cpp.

◆ GetBodyInertia() [2/2]

Eigen::Matrix< double, 3, 3 > Kinematics::GetBodyInertia ( BodyType  _body,
LegType  _leg 
)
private

Definition at line 2747 of file kinematics.cpp.

◆ GetflOffset()

bool Kinematics::GetflOffset ( )
inline

Definition at line 664 of file kinematics.h.

◆ GetfrOffset()

bool Kinematics::GetfrOffset ( )
inline

Definition at line 666 of file kinematics.h.

◆ GetrlOffset()

bool Kinematics::GetrlOffset ( )
inline

Definition at line 668 of file kinematics.h.

◆ GetrrOffset()

bool Kinematics::GetrrOffset ( )
inline

Definition at line 670 of file kinematics.h.

◆ GetDistanceFromBaseToFrontLeftHipInB()

Eigen::Matrix<double, 3, 1> Kinematics::GetDistanceFromBaseToFrontLeftHipInB ( )
inline

Definition at line 672 of file kinematics.h.

◆ GetDistanceFromBaseToFrontRightHipInB()

Eigen::Matrix<double, 3, 1> Kinematics::GetDistanceFromBaseToFrontRightHipInB ( )
inline

Definition at line 674 of file kinematics.h.

◆ GetDistanceFromBaseToRearLeftHipInB()

Eigen::Matrix<double, 3, 1> Kinematics::GetDistanceFromBaseToRearLeftHipInB ( )
inline

Definition at line 676 of file kinematics.h.

◆ GetDistanceFromBaseToRearRightHipInB()

Eigen::Matrix<double, 3, 1> Kinematics::GetDistanceFromBaseToRearRightHipInB ( )
inline

Definition at line 678 of file kinematics.h.

Member Data Documentation

◆ min_angles

JointSpaceVector Kinematics::min_angles
private

Minimum joint limits.

Definition at line 681 of file kinematics.h.

◆ max_angles

JointSpaceVector Kinematics::max_angles
private

Maximum joint limits.

Definition at line 684 of file kinematics.h.

◆ positionBaseToFrontLeftInB

Vector3d Kinematics::positionBaseToFrontLeftInB
private

Position vector relating the base coordinates to the front left hip.

Definition at line 688 of file kinematics.h.

◆ positionBaseToFrontRightInB

Vector3d Kinematics::positionBaseToFrontRightInB
private

Position vector relating the base coordinates to the front right hip.

Definition at line 692 of file kinematics.h.

◆ positionBaseToRearLeftInB

Vector3d Kinematics::positionBaseToRearLeftInB
private

Position vector relating the base coordinates to the rear left hip.

Definition at line 696 of file kinematics.h.

◆ positionBaseToRearRightInB

Vector3d Kinematics::positionBaseToRearRightInB
private

Position vector relating the base coordinates to the rear right hip.

Definition at line 700 of file kinematics.h.

◆ L1

double Kinematics::L1
private

Hip link length.

Definition at line 703 of file kinematics.h.

◆ L2

double Kinematics::L2
private

Thigh (Femur) link length.

Definition at line 706 of file kinematics.h.

◆ L3

double Kinematics::L3
private

Leg (Fibula & Tibia) link length.

Definition at line 709 of file kinematics.h.

◆ LC1

double Kinematics::LC1
private

Hip yaw joint to hip CoM length.

Definition at line 712 of file kinematics.h.

◆ LC2

double Kinematics::LC2
private

Hip pitch joint to thigh CoM length.

Definition at line 715 of file kinematics.h.

◆ LC3

double Kinematics::LC3
private

Knee pitch joint to leg CoM length.

Definition at line 718 of file kinematics.h.

◆ flOffset

bool Kinematics::flOffset
private

Front Left offset.

Definition at line 721 of file kinematics.h.

◆ frOffset

bool Kinematics::frOffset
private

Front Right offset.

Definition at line 724 of file kinematics.h.

◆ rlOffset

bool Kinematics::rlOffset
private

Rear Left offset.

Definition at line 727 of file kinematics.h.

◆ rrOffset

bool Kinematics::rrOffset
private

Rear Right offset.

Definition at line 730 of file kinematics.h.

◆ M0

double Kinematics::M0
private

Body link mass.

Definition at line 733 of file kinematics.h.

◆ M1

double Kinematics::M1
private

Hip link mass.

Definition at line 736 of file kinematics.h.

◆ M2

double Kinematics::M2
private

Thigh link mass.

Definition at line 739 of file kinematics.h.

◆ M3

double Kinematics::M3
private

Leg link mass.

Definition at line 742 of file kinematics.h.

◆ I0

Eigen::Matrix<double, 3, 3> Kinematics::I0
private

Body link inertia matrix.

Definition at line 745 of file kinematics.h.

◆ I1_fl_rr

Eigen::Matrix<double, 3, 3> Kinematics::I1_fl_rr
private

Front Left & Rear Right Hip link inertia matrix.

Definition at line 748 of file kinematics.h.

◆ I1_fr_rl

Eigen::Matrix<double, 3, 3> Kinematics::I1_fr_rl
private

Front Right & Rear Left Hip link inertia matrix.

Definition at line 751 of file kinematics.h.

◆ I2

Eigen::Matrix<double, 3, 3> Kinematics::I2
private

Thigh link inertia matrix.

Definition at line 754 of file kinematics.h.

◆ I3

Eigen::Matrix<double, 3, 3> Kinematics::I3
private

Leg link inertia matrix.

Definition at line 757 of file kinematics.h.


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