Centroidal Dynamics model relating forces to base accelerations. More...
#include <centroidal_model.h>
Public Member Functions | |
CentroidalModel (double mass, const Eigen::Matrix3d &inertia_b, int ee_count) | |
Constructs a specific Centroidal model. More... | |
CentroidalModel (double mass, double Ixx, double Iyy, double Izz, double Ixy, double Ixz, double Iyz, int ee_count) | |
Constructs a specific Centroidal model. More... | |
virtual BaseAcc | GetDynamicViolation () const override |
The violation of the system dynamics incurred by the current values. More... | |
virtual Jac | GetJacobianWrtBaseAng (const EulerConverter &base_angular, double t) const override |
How the base orientation affects the dynamic violation. More... | |
virtual 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... | |
virtual Jac | GetJacobianWrtEEPos (const Jac &jac_ee_pos, EE) const override |
How the endeffector positions affect the dynamic violation. More... | |
virtual Jac | GetJacobianWrtForce (const Jac &jac_force, EE) const override |
How the endeffector forces affect the dynamic violation. More... | |
virtual | ~CentroidalModel ()=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... | |
Private Attributes | |
Eigen::SparseMatrix< double, Eigen::RowMajor > | I_b |
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... | |
Centroidal Dynamics model relating forces to base accelerations.
This class implements a simplified Centroidal dynamics model, a reduced dimensional model, lying in terms of accuracy between a simple Linear Inverted Pendulum model and a complex full Centroidal (https://doi.org/10.1007/s10514-013-9341-4) or Rigid-body-dynamics Model.
This model makes the assumption that the motion of the limbs does not incur significant momentum and can therefore be neglected. This eliminates the often very nonnlinear dependency on joint angles and allows to express all quantities in Cartesian space.
Definition at line 53 of file centroidal_model.h.
towr::CentroidalModel::CentroidalModel | ( | double | mass, |
const Eigen::Matrix3d & | inertia_b, | ||
int | ee_count | ||
) |
Constructs a specific Centroidal model.
mass | The mass of the robot. |
ee_count | The number of endeffectors/forces. |
inertia_b | The elements of the 3x3 Inertia matrix around the CoM. This matrix maps angular accelerations expressed in base frame to Moments in base frame. |
Definition at line 69 of file centroidal_model.cc.
towr::CentroidalModel::CentroidalModel | ( | double | mass, |
double | Ixx, | ||
double | Iyy, | ||
double | Izz, | ||
double | Ixy, | ||
double | Ixz, | ||
double | Iyz, | ||
int | ee_count | ||
) |
Constructs a specific Centroidal model.
mass | Mass of the robot. |
I.. | Elements of the 3x3 Inertia matrix ( |
ee_count | Number of endeffectors/forces. |
Definition at line 59 of file centroidal_model.cc.
|
virtualdefault |
|
overridevirtual |
The violation of the system dynamics incurred by the current values.
Implements towr::DynamicModel.
Definition at line 77 of file centroidal_model.cc.
|
overridevirtual |
How the base orientation affects the dynamic violation.
base_angular | provides Euler angles Jacobians. |
t | Time at which euler angles values are queried. |
Implements towr::DynamicModel.
Definition at line 124 of file centroidal_model.cc.
|
overridevirtual |
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. |
Implements towr::DynamicModel.
Definition at line 104 of file centroidal_model.cc.
|
overridevirtual |
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. |
Implements towr::DynamicModel.
Definition at line 182 of file centroidal_model.cc.
|
overridevirtual |
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. |
Implements towr::DynamicModel.
Definition at line 168 of file centroidal_model.cc.
|
private |
Inertia of entire robot around the CoM expressed in a frame anchored in the base.
Definition at line 93 of file centroidal_model.h.