The Dynamics of the quadruped robot HyQ. More...
#include <hyq_model.h>
Public Member Functions | |
HyqDynamicModel () | |
Public Member Functions inherited from towr::SingleRigidBodyDynamics | |
BaseAcc | GetDynamicViolation () const override |
The violation of the system dynamics incurred by the current values. More... | |
Jac | GetJacobianWrtBaseAng (const EulerConverter &base_angular, double t) const override |
How the base orientation affects the dynamic violation. More... | |
Jac | GetJacobianWrtBaseLin (const Jac &jac_base_lin_pos, const Jac &jac_acc_base_lin) const override |
How the base position affects the dynamic violation. More... | |
Jac | GetJacobianWrtEEPos (const Jac &jac_ee_pos, EE) const override |
How the endeffector positions affect the dynamic violation. More... | |
Jac | GetJacobianWrtForce (const Jac &jac_force, EE) const override |
How the endeffector forces affect the dynamic violation. More... | |
SingleRigidBodyDynamics (double mass, const Eigen::Matrix3d &inertia_b, int ee_count) | |
Constructs a specific model. More... | |
SingleRigidBodyDynamics (double mass, double Ixx, double Iyy, double Izz, double Ixy, double Ixz, double Iyz, int ee_count) | |
Constructs a specific model. More... | |
virtual | ~SingleRigidBodyDynamics ()=default |
Public Member Functions inherited from towr::DynamicModel | |
double | g () const |
int | GetEECount () const |
the number of endeffectors that this robot has. More... | |
double | m () const |
void | SetCurrent (const ComPos &com_W, const Vector3d com_acc_W, const Matrix3d &w_R_b, const AngVel &omega_W, const Vector3d &omega_dot_W, const EELoad &force_W, const EEPos &pos_W) |
Sets the current state and input of the system. More... | |
Additional Inherited Members | |
Public Types inherited from towr::DynamicModel | |
using | AngVel = Eigen::Vector3d |
using | BaseAcc = Eigen::Matrix< double, 6, 1 > |
using | ComPos = Eigen::Vector3d |
using | EE = uint |
using | EELoad = EEPos |
using | EEPos = std::vector< Eigen::Vector3d > |
using | Jac = Eigen::SparseMatrix< double, Eigen::RowMajor > |
using | Matrix3d = Eigen::Matrix3d |
using | Ptr = std::shared_ptr< DynamicModel > |
using | Vector3d = Eigen::Vector3d |
Protected Member Functions inherited from towr::DynamicModel | |
DynamicModel (double mass, int ee_count) | |
Construct a dynamic object. Protected as this is abstract base class. More... | |
virtual | ~DynamicModel ()=default |
Protected Attributes inherited from towr::DynamicModel | |
Vector3d | com_acc_ |
x-y-z acceleration of the Center-of-Mass. More... | |
ComPos | com_pos_ |
x-y-z position of the Center-of-Mass. More... | |
EELoad | ee_force_ |
The endeffector force expressed in world frame. More... | |
EEPos | ee_pos_ |
The x-y-z position of each endeffector. More... | |
AngVel | omega_ |
angular velocity expressed in world frame. More... | |
Vector3d | omega_dot_ |
angular acceleration expressed in world frame. More... | |
Matrix3d | w_R_b_ |
rotation matrix from base (b) to world (w) frame. More... | |
The Dynamics of the quadruped robot HyQ.
Definition at line 62 of file hyq_model.h.
|
inline |
Definition at line 64 of file hyq_model.h.