30 #ifndef TOWR_MODELS_DYNAMIC_MODEL_H_ 31 #define TOWR_MODELS_DYNAMIC_MODEL_H_ 36 #include <Eigen/Dense> 37 #include <Eigen/Sparse> 60 using Ptr = std::shared_ptr<DynamicModel>;
65 using BaseAcc = Eigen::Matrix<double,6,1>;
66 using Jac = Eigen::SparseMatrix<double, Eigen::RowMajor>;
67 using EEPos = std::vector<Eigen::Vector3d>;
100 const Jac& jac_base_lin_acc)
const = 0;
136 double g()
const {
return g_; };
141 double m()
const {
return m_; };
Vector3d com_acc_
x-y-z acceleration of the Center-of-Mass.
virtual Jac GetJacobianWrtEEPos(const Jac &ee_pos, EE ee) const =0
How the endeffector positions affect the dynamic violation.
Matrix3d w_R_b_
rotation matrix from base (b) to world (w) frame.
std::vector< Eigen::Vector3d > EEPos
Eigen::Matrix< double, 6, 1 > BaseAcc
Vector3d omega_dot_
angular acceleration expressed in world frame.
ComPos com_pos_
x-y-z position of the Center-of-Mass.
AngVel omega_
angular velocity expressed in world frame.
Converts Euler angles and derivatives to angular quantities.
A interface for the the system dynamics of a legged robot.
std::shared_ptr< DynamicModel > Ptr
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.
EELoad ee_force_
The endeffector force expressed in world frame.
EEPos ee_pos_
The x-y-z position of each endeffector.
DynamicModel(double mass, int ee_count)
Construct a dynamic object. Protected as this is abstract base class.
double g_
gravity acceleration [m/s^2]
virtual Jac GetJacobianWrtBaseAng(const EulerConverter &base_angular, double t) const =0
How the base orientation affects the dynamic violation.
virtual ~DynamicModel()=default
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.
int GetEECount() const
the number of endeffectors that this robot has.
Eigen::SparseMatrix< double, Eigen::RowMajor > Jac
virtual BaseAcc GetDynamicViolation() const =0
The violation of the system dynamics incurred by the current values.
double m_
mass of the robot
virtual Jac GetJacobianWrtForce(const Jac &ee_force, EE ee) const =0
How the endeffector forces affect the dynamic violation.