37 double Ixy,
double Ixz,
double Iyz)
48 Cross(
const Eigen::Vector3d& in)
52 out.coeffRef(0,1) = -in(2); out.coeffRef(0,2) = in(1);
53 out.coeffRef(1,0) = in(2); out.coeffRef(1,2) = -in(0);
54 out.coeffRef(2,0) = -in(1); out.coeffRef(2,1) = in(0);
60 double Ixx,
double Iyy,
double Izz,
61 double Ixy,
double Ixz,
double Iyz,
73 I_b = inertia_b.sparseView();
82 f_sum.setZero(); tau_sum.setZero();
84 for (
int ee=0; ee<
ee_pos_.size(); ++ee) {
105 const Jac& jac_acc_base_lin)
const 108 int n = jac_pos_base_lin.cols();
112 Jac jac_tau =
Cross(f)*jac_pos_base_lin;
113 jac_tau_sum += jac_tau;
117 jac.middleRows(
AX,
k3D) = -jac_tau_sum;
118 jac.middleRows(
LX,
k3D) =
m()*jac_acc_base_lin;
139 Jac jac13 = I_w * jac_ang_acc;
140 Jac jac1 = jac11 + jac12 + jac13;
154 Jac jac23 = I_w * jac_ang_vel;
160 int n = jac_ang_vel.cols();
162 jac.middleRows(
AX,
k3D) = jac1 + jac2;
173 int n = jac_force.cols();
175 jac.middleRows(
AX,
k3D) = -jac_tau;
176 jac.middleRows(
LX,
k3D) = -jac_force;
185 Jac jac_tau =
Cross(f)*(-jac_ee_pos);
187 Jac jac(
k6D, jac_tau.cols());
188 jac.middleRows(
AX,
k3D) = -jac_tau;
Vector3d com_acc_
x-y-z acceleration of the Center-of-Mass.
Matrix3d w_R_b_
rotation matrix from base (b) to world (w) frame.
virtual Jac GetJacobianWrtEEPos(const Jac &jac_ee_pos, EE) const override
How the endeffector positions affect the dynamic violation.
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.
Jacobian GetDerivOfAngAccWrtEulerNodes(double t) const
Jacobian of the angular acceleration with respect to the Euler nodes.
EELoad ee_force_
The endeffector force expressed in world frame.
EEPos ee_pos_
The x-y-z position of each endeffector.
CentroidalModel::Jac Cross(const Eigen::Vector3d &in)
virtual Jac GetJacobianWrtBaseAng(const EulerConverter &base_angular, double t) const override
How the base orientation affects the dynamic violation.
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.
virtual BaseAcc GetDynamicViolation() const override
The violation of the system dynamics incurred by the current values.
Eigen::SparseMatrix< double, Eigen::RowMajor > I_b
Centroidal Dynamics model relating forces to base accelerations.
Jacobian GetDerivOfAngVelWrtEulerNodes(double t) const
Jacobian of the angular velocity with respect to the Euler nodes.
Eigen::SparseMatrix< double, Eigen::RowMajor > Jac
CentroidalModel(double mass, const Eigen::Matrix3d &inertia_b, int ee_count)
Constructs a specific Centroidal model.
Jacobian DerivOfRotVecMult(double t, const Vector3d &v, bool inverse) const
Returns the derivative of result of the linear equation M*v.
virtual Jac GetJacobianWrtForce(const Jac &jac_force, EE) const override
How the endeffector forces affect the dynamic violation.
static Eigen::Matrix3d BuildInertiaTensor(double Ixx, double Iyy, double Izz, double Ixy, double Ixz, double Iyz)