Quadruped Chassis.
More...
#include <Chassis.hpp>
|
| | Chassis (Eigen::Matrix6d &G, Eigen::Isometry3d &Ms, std::array< Eigen::Isometry3d, 4 > &M01) |
| | Chassis Constructor.
|
| bool | ik (const Eigen::Isometry3d &Ts0, const std::array< Eigen::Isometry3d, 4 > &T4, std::array< Eigen::Vector3d, 4 > &pf, Eigen::Matrix< double, 6, 12 > *Jinv) |
| | Inverse Kinematics.
|
| bool | ivk (const Eigen::Vector6d &Vb, const Eigen::Matrix< double, 6, 12 > &Jinv, std::array< Eigen::Vector3d, 4 > &vf) |
| | Inverse Velocity Kinematics.
|
| bool | id (std::array< Eigen::Vector3d, 4 > &ff) |
| | Inverse Dynamics.
|
| bool | nvp (const Eigen::Vector6d &F, const std::array< std::shared_ptr< Leg >, 4 > &legs, double &K) |
| | Margin of Static Stability.
|
|
void | run () |
|
|
Eigen::Isometry3d | Ts0 |
| | Tf chassis in home frame [SE(3)].
|
|
Eigen::Vector6d | Vb |
| | Chassis twist [rad/s; m/s].
|
|
Eigen::Vector6d | dVb |
| | Chassis spatial acceleration [rad/s^2; m/s^2].
|
|
Eigen::Vector6d | Fb |
| | Chassis wrench [N*m; m].
|
|
double | K |
| | Lowest normalized virtual power.
|
|
int | iRolloverLeg |
| | Index of leg with lowest bordering K (next leg to step).
|
|
std::array< Eigen::Isometry3d, 4 > | T4 |
| | Tf legs in the space frame [SE(3)].
|
|
std::array< std::shared_ptr< Leg >, 4 > | legs |
| | Array of Leg shared pointers.
|
|
Eigen::Hyperplane< double, 3 > | footPlane |
| | Foot Plane.
|
|
|
const Eigen::Matrix6d | G |
| | Spatial inertia matrix [kg*m^2; m].
|
|
const Eigen::Isometry3d | Ms |
| | Tf chassis home in the space frame [SE(3)].
|
|
const std::array< Eigen::Isometry3d, 4 > | M01 |
| | Tf legs in the chassis body frame [SE(3)].
|
|
Eigen::Matrix< double, 6, 12 > | Jinv |
| | 6x12 Inverse Jacobian
|
|
const Eigen::Vector3d | g {0, 0, 9.81} |
| | Gravity vector [m/s^2].
|
Quadruped Chassis.
The chassis class contains gemotry and mass properties for the chassis, the chassis state, and functions to operate on the chassis state.
- {b} is the chassis "body" frame, at the volumetric center of the chassis
- {1} is the shoulder frame
- {4} is the foot frame, different for each foot
◆ Chassis()
| Chassis::Chassis |
( |
Eigen::Matrix6d & | G, |
|
|
Eigen::Isometry3d & | Ms, |
|
|
std::array< Eigen::Isometry3d, 4 > & | M01 ) |
|
inline |
Chassis Constructor.
- Parameters
-
| [in] | G | 6x6 spatial inertia matrix for the chassis |
| [in] | Ms | Home transform of the chassis in the base frame |
| [in] | M01 | Array of transforms from the chassis frame to the leg base frames |
◆ id()
| bool Chassis::id |
( |
std::array< Eigen::Vector3d, 4 > & | ff | ) |
|
Inverse Dynamics.
Compute foot force from chassis state
- Parameters
-
| [out] | ff | Array of 3-vector resultant foot forces |
◆ ik()
| bool Chassis::ik |
( |
const Eigen::Isometry3d & | Ts0, |
|
|
const std::array< Eigen::Isometry3d, 4 > & | T4, |
|
|
std::array< Eigen::Vector3d, 4 > & | pf, |
|
|
Eigen::Matrix< double, 6, 12 > * | Jinv ) |
Inverse Kinematics.
Compute foot poses (and Jacobian inverse) at a given chassis pose
- Parameters
-
| [in] | Ts0 | SE(3) transform of the chassis in the chassis home frame |
| [in] | T4 | Array of SE(3) transforms of the legs in the base frame |
| [out] | pf | Array of 3-vector resultant foot positions in the leg base frame |
| [out] | Jinv | 6x12 resultant Jacobian inverse (dfoot/dT) |
◆ ivk()
| bool Chassis::ivk |
( |
const Eigen::Vector6d & | Vb, |
|
|
const Eigen::Matrix< double, 6, 12 > & | Jinv, |
|
|
std::array< Eigen::Vector3d, 4 > & | vf ) |
Inverse Velocity Kinematics.
Compute foot velocities for a given chassis twist
- Parameters
-
| [in] | Vb | 6-vector twist of the chassis body |
| [in] | Jinv | 6x12 Jacobian inverse (dfoot/dT) |
| [out] | vf | Array of 3-vector resultant foot velocities |
◆ nvp()
| bool Chassis::nvp |
( |
const Eigen::Vector6d & | F, |
|
|
const std::array< std::shared_ptr< Leg >, 4 > & | legs, |
|
|
double & | K ) |
Margin of Static Stability.
Compute the minimum Normalized Virtual Power required for rollover in the current state
- Parameters
-
| [in] | F | Chassis wrench in the space frame |
| [in] | pf | Array of 3-vector resultant foot positions in the leg base frame |
| [out] | K | Minimum Normalized Virtual Power |
The documentation for this class was generated from the following files: