Dynamics model relating forces to base accelerations. More...
#include <single_rigid_body_dynamics.h>
Public Member Functions | |
BaseAcc | GetDynamicViolation () const override |
The violation of the system dynamics incurred by the current values. | |
Jac | GetJacobianWrtBaseAng (const EulerConverter &base_angular, double t) const override |
How the base orientation affects the dynamic violation. | |
Jac | GetJacobianWrtBaseLin (const Jac &jac_base_lin_pos, const Jac &jac_acc_base_lin) const override |
How the base position affects the dynamic violation. | |
Jac | GetJacobianWrtEEPos (const Jac &jac_ee_pos, EE) const override |
How the endeffector positions affect the dynamic violation. | |
Jac | GetJacobianWrtForce (const Jac &jac_force, EE) const override |
How the endeffector forces affect the dynamic violation. | |
SingleRigidBodyDynamics (double mass, const Eigen::Matrix3d &inertia_b, int ee_count) | |
Constructs a specific model. | |
SingleRigidBodyDynamics (double mass, double Ixx, double Iyy, double Izz, double Ixy, double Ixz, double Iyz, int ee_count) | |
Constructs a specific model. | |
virtual | ~SingleRigidBodyDynamics () |
Private Attributes | |
Eigen::SparseMatrix< double, Eigen::RowMajor > | I_b |
Dynamics model relating forces to base accelerations.
This class implements a Single Rigid Body dynamics model, a reduced dimensional model, lying in terms of accuracy between a Linear Inverted Pendulum model and a full Centroidal 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 nonlinear dependency on joint angles and allows to express all quantities in Cartesian space.
For the derivation and all assumptions of this model, see: https://doi.org/10.3929/ethz-b-000272432
Definition at line 56 of file single_rigid_body_dynamics.h.
towr::SingleRigidBodyDynamics::SingleRigidBodyDynamics | ( | double | mass, |
const Eigen::Matrix3d & | inertia_b, | ||
int | ee_count | ||
) |
Constructs a specific 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 single_rigid_body_dynamics.cc.
towr::SingleRigidBodyDynamics::SingleRigidBodyDynamics | ( | double | mass, |
double | Ixx, | ||
double | Iyy, | ||
double | Izz, | ||
double | Ixy, | ||
double | Ixz, | ||
double | Iyz, | ||
int | ee_count | ||
) |
Constructs a specific 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 single_rigid_body_dynamics.cc.
virtual towr::SingleRigidBodyDynamics::~SingleRigidBodyDynamics | ( | ) | [virtual] |
SingleRigidBodyDynamics::BaseAcc towr::SingleRigidBodyDynamics::GetDynamicViolation | ( | ) | const [override, virtual] |
The violation of the system dynamics incurred by the current values.
Implements towr::DynamicModel.
Definition at line 77 of file single_rigid_body_dynamics.cc.
SingleRigidBodyDynamics::Jac towr::SingleRigidBodyDynamics::GetJacobianWrtBaseAng | ( | const EulerConverter & | base_angular, |
double | t | ||
) | const [override, virtual] |
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 single_rigid_body_dynamics.cc.
SingleRigidBodyDynamics::Jac towr::SingleRigidBodyDynamics::GetJacobianWrtBaseLin | ( | const Jac & | jac_base_lin_pos, |
const Jac & | jac_base_lin_acc | ||
) | const [override, 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. |
Implements towr::DynamicModel.
Definition at line 104 of file single_rigid_body_dynamics.cc.
SingleRigidBodyDynamics::Jac towr::SingleRigidBodyDynamics::GetJacobianWrtEEPos | ( | const Jac & | ee_pos, |
EE | ee | ||
) | const [override, 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. |
Implements towr::DynamicModel.
Definition at line 182 of file single_rigid_body_dynamics.cc.
SingleRigidBodyDynamics::Jac towr::SingleRigidBodyDynamics::GetJacobianWrtForce | ( | const Jac & | ee_force, |
EE | ee | ||
) | const [override, 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. |
Implements towr::DynamicModel.
Definition at line 168 of file single_rigid_body_dynamics.cc.
Eigen::SparseMatrix<double, Eigen::RowMajor> towr::SingleRigidBodyDynamics::I_b [private] |
Inertia of entire robot around the CoM expressed in a frame anchored in the base.
Definition at line 95 of file single_rigid_body_dynamics.h.