30 #ifndef TOWR_MODELS_SINGLE_RIBID_BODY_DYNAMICS_MODEL_H_ 31 #define TOWR_MODELS_SINGLE_RIBID_BODY_DYNAMICS_MODEL_H_ 75 double Ixx,
double Iyy,
double Izz,
76 double Ixy,
double Ixz,
double Iyz,
84 const Jac& jac_acc_base_lin)
const override;
86 double t)
const override;
95 Eigen::SparseMatrix<double, Eigen::RowMajor>
I_b;
SingleRigidBodyDynamics(double mass, const Eigen::Matrix3d &inertia_b, int ee_count)
Constructs a specific model.
Jac GetJacobianWrtBaseLin(const Jac &jac_base_lin_pos, const Jac &jac_acc_base_lin) const override
How the base position affects the dynamic violation.
Eigen::Matrix< double, 6, 1 > BaseAcc
virtual ~SingleRigidBodyDynamics()=default
Converts Euler angles and derivatives to angular quantities.
A interface for the the system dynamics of a legged robot.
Jac GetJacobianWrtForce(const Jac &jac_force, EE) const override
How the endeffector forces affect the dynamic violation.
Eigen::SparseMatrix< double, Eigen::RowMajor > I_b
Jac GetJacobianWrtBaseAng(const EulerConverter &base_angular, double t) const override
How the base orientation affects the dynamic violation.
BaseAcc GetDynamicViolation() const override
The violation of the system dynamics incurred by the current values.
Eigen::SparseMatrix< double, Eigen::RowMajor > Jac
Dynamics model relating forces to base accelerations.
Jac GetJacobianWrtEEPos(const Jac &jac_ee_pos, EE) const override
How the endeffector positions affect the dynamic violation.