Tetrapod Project
|
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... | |
A class for analytical Kinematics Solving.
Definition at line 53 of file kinematics.h.
enum Kinematics::LegType |
Leg type enumerator.
Enumerator | |
---|---|
frontLeft | |
frontRight | |
rearLeft | |
rearRight | |
NONE |
Definition at line 56 of file kinematics.h.
enum Kinematics::BodyType |
Kinematics::Kinematics | ( | ) |
Constructor.
Definition at line 31 of file kinematics.cpp.
|
virtual |
Destructor.
Definition at line 101 of file kinematics.cpp.
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.
[in] | _q | Generalized coordinates. containing the floating base and joint positions. |
[out] | _f_pos | Footstep positions generated from solving the forward kinematics. |
Definition at line 165 of file kinematics.cpp.
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.
[in] | _q_b | Base Pose in the world frame. |
[in] | _f_pos | Footstep positions in the world frame. |
[out] | _q_r | Joint angles from the Inverse Kinematics solution. |
Definition at line 104 of file kinematics.cpp.
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.
[in] | _h_pos | Hip position in world frame. |
[in] | _theta_hy | Hip yaw angle. |
[in] | _theta_hp | Hip pitch angle. |
[in] | _theta_kp | Knee pitch angle. |
Definition at line 229 of file kinematics.cpp.
The SolveSingleLegForwardKinematics function calculates the foot position in the hip frame.
[in] | _joint_angles | A vector containing the hip yaw, hip pitch and knee pitch angles |
Definition at line 289 of file kinematics.cpp.
Vector3d Kinematics::SolveSingleLegForwardKinematics | ( | const LegType & | _leg_type, |
const Vector3d & | _joint_angles | ||
) |
The SolveSingleLegForwardKinematics function calculates the foot position in the hip frame.
[in] | _leg_type | Indicates which leg it is |
[in] | _joint_angles | A vector containing the hip yaw, hip pitch and knee pitch angles |
Definition at line 248 of file kinematics.cpp.
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.
[in] | _leg_type | Indicates which leg it is |
[in] | _joint_angles | A vector containing the hip yaw, hip pitch and knee pitch angles |
Definition at line 262 of file kinematics.cpp.
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.
[in] | _offset | Bool 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_pos | Hip position in world frame. |
[in] | _f_pos | Foot position in world frame. |
[out] | _joint_angles | Joint angles from the Inverse Kinematics solution for a single-leg (sl). |
Definition at line 296 of file kinematics.cpp.
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.
[in] | _offset | Bool 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_pos | Foot position in hip frame. |
[out] | _joint_angles | Joint angles from the Inverse Kinematics solution for a single-leg (sl). |
Definition at line 362 of file kinematics.cpp.
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.
[in] | _a | Link length. |
[in] | _alpha | Link twist. |
[in] | _d | Link offset. |
[in] | _theta | Joint angle. |
Definition at line 369 of file kinematics.cpp.
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.
[in] | _leg | Leg type. |
[in] | _body | Body type. |
[in] | _theta_hy | Hip yaw angle. |
[in] | _theta_hp | Hip pitch angle. |
[in] | _theta_kp | Knee pitch angle. |
Definition at line 389 of file kinematics.cpp.
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.
[in] | _roll | Roll angle (x-axis). |
[in] | _pitch | Pitch angle (y-axis). |
[in] | _yaw | Yaw angle (z-axis). |
Definition at line 539 of file kinematics.cpp.
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.
[in] | _roll | Roll angle (x-axis). |
[in] | _pitch | Pitch angle (y-axis). |
[in] | _yaw | Yaw angle (z-axis). |
[in] | _roll_rate | Roll rate (x-axis). |
[in] | _pitch_rate | Pitch rate (y-axis). |
[in] | _yaw_rate | Yaw rate (z-axis). |
Definition at line 552 of file kinematics.cpp.
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.
[in] | _roll | Roll angle (x-axis). |
[in] | _pitch | Pitch angle (y-axis). |
[in] | _yaw | Yaw angle (z-axis). |
Definition at line 574 of file kinematics.cpp.
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.
[in] | _roll | Roll angle (x-axis). |
[in] | _pitch | Pitch angle (y-axis). |
[in] | _yaw | Yaw angle (z-axis). |
[in] | _roll_rate | Roll rate (x-axis). |
[in] | _pitch_rate | Pitch rate (y-axis). |
[in] | _yaw_rate | Yaw rate (z-axis). |
Definition at line 587 of file kinematics.cpp.
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.
[in] | _roll | Roll angle (x-axis). |
[in] | _pitch | Pitch angle (y-axis). |
[in] | _yaw | Yaw angle (z-axis). |
Definition at line 609 of file kinematics.cpp.
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.
[in] | _roll | Roll angle (x-axis). |
[in] | _pitch | Pitch angle (y-axis). |
[in] | _yaw | Yaw angle (z-axis). |
[in] | _roll_rate | Roll rate (x-axis). |
[in] | _pitch_rate | Pitch rate (y-axis). |
[in] | _yaw_rate | Yaw rate (z-axis). |
Definition at line 622 of file kinematics.cpp.
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.
[in] | _leg | Leg type. |
[in] | _body | Body type. |
[in] | _q | Generalized coordinates. |
Definition at line 644 of file kinematics.cpp.
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.
[in] | _leg | Leg type. |
[in] | _body | Body type. |
[in] | _theta_hy | Hip yaw angle. |
[in] | _theta_hp | Hip pitch angle. |
[in] | _theta_kp | Knee pitch angle. |
Definition at line 723 of file kinematics.cpp.
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.
[in] | _leg | Leg type. |
[in] | _body | Body type. |
[in] | _q_r | Joint coordinates. |
Definition at line 840 of file kinematics.cpp.
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.
[in] | _leg | Leg type. |
[in] | _body | Body type. |
[in] | _q | Generalized coordinates. |
Definition at line 911 of file kinematics.cpp.
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.
[in] | _leg | Leg type. |
[in] | _body | Body type. |
[in] | _q | Generalized coordinates. |
Definition at line 969 of file kinematics.cpp.
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.
[in] | _leg | Leg type. |
[in] | _body | Body type. |
[in] | _theta_hy | Hip yaw angle. |
[in] | _theta_hp | Hip pitch angle. |
[in] | _theta_kp | Knee pitch angle. |
[in] | _dot_theta_hy | Hip yaw rate. |
[in] | _dot_theta_hp | Hip pitch rate. |
[in] | _dot_theta_kp | Knee pitch rate. |
Definition at line 1027 of file kinematics.cpp.
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.
[in] | _leg | Leg type. |
[in] | _body | Body type. |
[in] | _q_r | Joint coordinates. |
[in] | _dot_q_r | Joint velocities. |
Definition at line 1159 of file kinematics.cpp.
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.
[in] | _leg | Leg type. |
[in] | _body | Body type. |
[in] | _q | Generalized coordinates. |
[in] | _u | Generalized velocities. |
Definition at line 1254 of file kinematics.cpp.
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.
[in] | _leg | Leg type. |
[in] | _body | Body type. |
[in] | _q | Generalized coordinates. |
[in] | _u | Generalized velocities. |
Definition at line 1337 of file kinematics.cpp.
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.
[in] | _leg | Leg type. |
[in] | _body | Body type. |
[in] | _theta_hy | Hip yaw angle. |
[in] | _theta_hp | Hip pitch angle. |
[in] | _theta_kp | Knee pitch angle. |
Definition at line 1420 of file kinematics.cpp.
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.
[in] | _leg | Leg type. |
[in] | _body | Body type. |
[in] | _q_r | Joint coordinates. |
Definition at line 1540 of file kinematics.cpp.
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.
[in] | _leg | Leg type. |
[in] | _body | Body type. |
[in] | _q | Generalized coordinates. |
Definition at line 1611 of file kinematics.cpp.
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.
[in] | _leg | Leg type. |
[in] | _body | Body type. |
[in] | _q | Generalized coordinates. |
Definition at line 1661 of file kinematics.cpp.
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.
[in] | _leg | Leg type. |
[in] | _body | Body type. |
[in] | _theta_hy | Hip yaw angle. |
[in] | _theta_hp | Hip pitch angle. |
[in] | _theta_kp | Knee pitch angle. |
[in] | _dot_theta_hy | Hip yaw rate. |
[in] | _dot_theta_hp | Hip pitch rate. |
[in] | _dot_theta_kp | Knee pitch rate. |
Definition at line 1711 of file kinematics.cpp.
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.
[in] | _leg | Leg type. |
[in] | _body | Body type. |
[in] | _q_r | Joint coordinates. |
[in] | _dot_q_r | Joint velocities. |
Definition at line 1822 of file kinematics.cpp.
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.
[in] | _leg | Leg type. |
[in] | _body | Body type. |
[in] | _q | Generalized coordinates. |
[in] | _u | Generalized velocities. |
Definition at line 1917 of file kinematics.cpp.
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.
[in] | _leg | Leg type. |
[in] | _body | Body type. |
[in] | _q | Generalized coordinates. |
[in] | _u | Generalized velocities. |
Definition at line 1991 of file kinematics.cpp.
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.
[in] | _leg | Leg type. |
[in] | _q | Generalized coordinates. |
Definition at line 2065 of file kinematics.cpp.
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.
[in] | _leg | Leg type. |
[in] | _q | Generalized coordinates. |
[in] | _u | Generalized velocities. |
Definition at line 2083 of file kinematics.cpp.
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.
[in] | _legs | A vector of leg types containing the contact points. |
[in] | _q | Generalized coordinates. |
Definition at line 2104 of file kinematics.cpp.
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.
[in] | _legs | A vector of leg types containing the contact points. |
[in] | _q | Generalized coordinates. |
[in] | _u | Generalized velocities. |
Definition at line 2156 of file kinematics.cpp.
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)
[in] | _legs | A vector of leg types containing the swing legs. |
[in] | _q | Generalized coordinates. |
Definition at line 2210 of file kinematics.cpp.
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)
[in] | _legs | A vector of leg types containing the swing legs. |
[in] | _q | Generalized coordinates. |
[in] | _u | Generalized velocities. |
Definition at line 2259 of file kinematics.cpp.
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.
[in] | _leg | Leg type. |
[in] | _body | Body type. |
[in] | _q | Generalized coordinates. |
Definition at line 2309 of file kinematics.cpp.
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.
[in] | _q | Generalized coordinates. |
Definition at line 2330 of file kinematics.cpp.
Eigen::Matrix< double, 3, 3 > Kinematics::GetSingleLegMassMatrix | ( | const Eigen::Matrix< double, 3, 1 > & | _q | ) |
Definition at line 2363 of file kinematics.cpp.
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.
[in] | _leg | Leg type. |
[in] | _body | Body type. |
[in] | _q | Generalized coordinates. |
[in] | _u | Generalized velocities. |
Definition at line 2386 of file kinematics.cpp.
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.
[in] | _q | Generalized coordinates. |
[in] | _u | Generalized velocities. |
Definition at line 2419 of file kinematics.cpp.
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.
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.
[in] | _leg | Leg type. |
[in] | _body | Body type. |
[in] | _q | Generalized coordinates. |
Definition at line 2488 of file kinematics.cpp.
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.
[in] | _q | Generalized coordinates. |
Definition at line 2543 of file kinematics.cpp.
Eigen::Matrix< double, 3, 1 > Kinematics::GetSingleLegGravitationalTerms | ( | const Eigen::Matrix< double, 3, 1 > & | _q | ) |
Definition at line 2578 of file kinematics.cpp.
bool Kinematics::ValidateSolution | ( | const JointSpaceVector & | _q_r | ) |
The ValidateSolution function evaluates whether a set of joint angles is within joint limits.
[in] | _q_r | Joint angles generated by the IK solver. |
Definition at line 2603 of file kinematics.cpp.
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.
[in] | _q_r | Joint angles for a single leg generated by the IK solver. |
Definition at line 2622 of file kinematics.cpp.
|
private |
The GetInertiaMatrix function returns the inertia matrix from the six inertial parameters.
[in] | _I_XX | inertia about the x axis |
[in] | _I_YY | inertia about the y axis |
[in] | _I_ZZ | inertia about the z axis |
[in] | _I_XY | inertia about the xy axis |
[in] | _I_XZ | inertia about the xz axis |
[in] | _I_YZ | inertia about the yz axis |
Definition at line 2642 of file kinematics.cpp.
|
private |
Definition at line 2663 of file kinematics.cpp.
|
private |
Definition at line 2705 of file kinematics.cpp.
Definition at line 2747 of file kinematics.cpp.
|
inline |
Definition at line 664 of file kinematics.h.
|
inline |
Definition at line 666 of file kinematics.h.
|
inline |
Definition at line 668 of file kinematics.h.
|
inline |
Definition at line 670 of file kinematics.h.
|
inline |
Definition at line 672 of file kinematics.h.
|
inline |
Definition at line 674 of file kinematics.h.
|
inline |
Definition at line 676 of file kinematics.h.
|
inline |
Definition at line 678 of file kinematics.h.
|
private |
Minimum joint limits.
Definition at line 681 of file kinematics.h.
|
private |
Maximum joint limits.
Definition at line 684 of file kinematics.h.
|
private |
Position vector relating the base coordinates to the front left hip.
Definition at line 688 of file kinematics.h.
|
private |
Position vector relating the base coordinates to the front right hip.
Definition at line 692 of file kinematics.h.
|
private |
Position vector relating the base coordinates to the rear left hip.
Definition at line 696 of file kinematics.h.
|
private |
Position vector relating the base coordinates to the rear right hip.
Definition at line 700 of file kinematics.h.
|
private |
Hip link length.
Definition at line 703 of file kinematics.h.
|
private |
Thigh (Femur) link length.
Definition at line 706 of file kinematics.h.
|
private |
Leg (Fibula & Tibia) link length.
Definition at line 709 of file kinematics.h.
|
private |
Hip yaw joint to hip CoM length.
Definition at line 712 of file kinematics.h.
|
private |
Hip pitch joint to thigh CoM length.
Definition at line 715 of file kinematics.h.
|
private |
Knee pitch joint to leg CoM length.
Definition at line 718 of file kinematics.h.
|
private |
Front Left offset.
Definition at line 721 of file kinematics.h.
|
private |
Front Right offset.
Definition at line 724 of file kinematics.h.
|
private |
Rear Left offset.
Definition at line 727 of file kinematics.h.
|
private |
Rear Right offset.
Definition at line 730 of file kinematics.h.
|
private |
Body link mass.
Definition at line 733 of file kinematics.h.
|
private |
Hip link mass.
Definition at line 736 of file kinematics.h.
|
private |
Thigh link mass.
Definition at line 739 of file kinematics.h.
|
private |
Leg link mass.
Definition at line 742 of file kinematics.h.
|
private |
Body link inertia matrix.
Definition at line 745 of file kinematics.h.
|
private |
Front Left & Rear Right Hip link inertia matrix.
Definition at line 748 of file kinematics.h.
|
private |
Front Right & Rear Left Hip link inertia matrix.
Definition at line 751 of file kinematics.h.
|
private |
Thigh link inertia matrix.
Definition at line 754 of file kinematics.h.
|
private |
Leg link inertia matrix.
Definition at line 757 of file kinematics.h.