A interface for the the system dynamics of a legged robot. More...
#include <dynamic_model.h>

| Public Types | |
| 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 | 
| Public Member Functions | |
| double | g () const | 
| virtual BaseAcc | GetDynamicViolation () const =0 | 
| The violation of the system dynamics incurred by the current values.  More... | |
| int | GetEECount () const | 
| the number of endeffectors that this robot has.  More... | |
| virtual Jac | GetJacobianWrtBaseAng (const EulerConverter &base_angular, double t) const =0 | 
| How the base orientation affects the dynamic violation.  More... | |
| virtual Jac | GetJacobianWrtBaseLin (const Jac &jac_base_lin_pos, const Jac &jac_base_lin_acc) const =0 | 
| How the base position affects the dynamic violation.  More... | |
| virtual Jac | GetJacobianWrtEEPos (const Jac &ee_pos, EE ee) const =0 | 
| How the endeffector positions affect the dynamic violation.  More... | |
| virtual Jac | GetJacobianWrtForce (const Jac &ee_force, EE ee) const =0 | 
| How the endeffector forces affect the dynamic violation.  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... | |
| Protected Member Functions | |
| DynamicModel (double mass, int ee_count) | |
| Construct a dynamic object. Protected as this is abstract base class.  More... | |
| virtual | ~DynamicModel ()=default | 
| Protected Attributes | |
| 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... | |
| Private Attributes | |
| double | g_ | 
| gravity acceleration [m/s^2]  More... | |
| double | m_ | 
| mass of the robot  More... | |
A interface for the the system dynamics of a legged robot.
This class is responsible for verifying that the current acceleration of a system given a specific robot state and input forces ensure the system dynamics, so g = xdd(t) - f(x(t), f(t)).
This model is used in DynamicConstraint to ensure that the optimized motion trajectory complies to this.
Currently, only CentroidalModel is implemented, but this can be extended in the future to also incorporate full rigid body dynamics. This interface to the solver should remain the same.
Definition at line 58 of file dynamic_model.h.
| using towr::DynamicModel::AngVel = Eigen::Vector3d | 
Definition at line 64 of file dynamic_model.h.
| using towr::DynamicModel::BaseAcc = Eigen::Matrix<double,6,1> | 
Definition at line 65 of file dynamic_model.h.
| using towr::DynamicModel::ComPos = Eigen::Vector3d | 
Definition at line 63 of file dynamic_model.h.
| using towr::DynamicModel::EE = uint | 
Definition at line 69 of file dynamic_model.h.
| using towr::DynamicModel::EELoad = EEPos | 
Definition at line 68 of file dynamic_model.h.
| using towr::DynamicModel::EEPos = std::vector<Eigen::Vector3d> | 
Definition at line 67 of file dynamic_model.h.
| using towr::DynamicModel::Jac = Eigen::SparseMatrix<double, Eigen::RowMajor> | 
Definition at line 66 of file dynamic_model.h.
| using towr::DynamicModel::Matrix3d = Eigen::Matrix3d | 
Definition at line 62 of file dynamic_model.h.
| using towr::DynamicModel::Ptr = std::shared_ptr<DynamicModel> | 
Definition at line 60 of file dynamic_model.h.
| using towr::DynamicModel::Vector3d = Eigen::Vector3d | 
Definition at line 61 of file dynamic_model.h.
| 
 | protected | 
Construct a dynamic object. Protected as this is abstract base class.
| mass | The mass of the system. | 
Definition at line 34 of file dynamic_model.cc.
| 
 | protectedvirtualdefault | 
| 
 | inline | 
Definition at line 136 of file dynamic_model.h.
| 
 | pure virtual | 
The violation of the system dynamics incurred by the current values.
Implemented in towr::CentroidalModel.
| 
 | inline | 
the number of endeffectors that this robot has.
Definition at line 146 of file dynamic_model.h.
| 
 | pure virtual | 
How the base orientation affects the dynamic violation.
| base_angular | provides Euler angles Jacobians. | 
| t | Time at which euler angles values are queried. | 
Implemented in towr::CentroidalModel.
| 
 | pure virtual | 
How the base position affects the dynamic violation.
| jac_base_lin_pos | The 3xn Jacobian of the base linear position. | 
| jac_base_lin_acc | The 3xn Jacobian of the base linear acceleration. | 
Implemented in towr::CentroidalModel.
| 
 | pure virtual | 
How the endeffector positions affect the dynamic violation.
| ee_force | The 3xn Jacobian of the foot position x,y,z. | 
| ee | The endeffector for which the senstivity is required. | 
Implemented in towr::CentroidalModel.
| 
 | pure virtual | 
How the endeffector forces affect the dynamic violation.
| ee_force | The 3xn Jacobian of the foot force x,y,z. | 
| ee | The endeffector for which the senstivity is required. | 
Implemented in towr::CentroidalModel.
| 
 | inline | 
Definition at line 141 of file dynamic_model.h.
| void towr::DynamicModel::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.
| com_W | Current Center-of-Mass (x,y,z) position in world frame. | 
| com_acc_W | Current Center-of-Mass (x,y,z) acceleration in world. | 
| w_R_b | Current rotation from base to world frame. | 
| omega_W | Current angular velocity in world frame. | 
| omega_dot_W | Current angular acceleration in world frame. | 
| force_W | Force at each foot expressed in world frame. | 
| pos_W | Position of each foot expressed in world frame | 
Definition at line 51 of file dynamic_model.cc.
| 
 | protected | 
x-y-z acceleration of the Center-of-Mass.
Definition at line 150 of file dynamic_model.h.
| 
 | protected | 
x-y-z position of the Center-of-Mass.
Definition at line 146 of file dynamic_model.h.
| 
 | protected | 
The endeffector force expressed in world frame.
Definition at line 157 of file dynamic_model.h.
| 
 | protected | 
The x-y-z position of each endeffector.
Definition at line 156 of file dynamic_model.h.
| 
 | private | 
gravity acceleration [m/s^2]
Definition at line 167 of file dynamic_model.h.
| 
 | private | 
mass of the robot
Definition at line 168 of file dynamic_model.h.
| 
 | protected | 
angular velocity expressed in world frame.
Definition at line 153 of file dynamic_model.h.
| 
 | protected | 
angular acceleration expressed in world frame.
Definition at line 154 of file dynamic_model.h.
| 
 | protected | 
rotation matrix from base (b) to world (w) frame.
Definition at line 152 of file dynamic_model.h.