Public Types | |
typedef Eigen::Matrix< double, 3, Eigen::Dynamic > | Matrix3x |
The 3d jacobian type (temporary) | |
typedef SE3::Vector3 | Vector3 |
typedef Eigen::Matrix< double, 6, 6, Eigen::RowMajor > | RowMatrix6 |
typedef Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > | RowMatrixXd |
Public Member Functions | |
Data (const Model &model) | |
Default constructor of se3::Data from a se3::Model. More... | |
Public Attributes | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef Eigen::Matrix< double, 6, Eigen::Dynamic > | Matrix6x |
The 6d jacobian type (temporary) | |
JointDataVector | joints |
Vector of se3::JointData associated to the se3::JointModel stored in model, encapsulated in JointDataAccessor. | |
container::aligned_vector< Motion > | a |
Vector of joint accelerations expressed at the centers of the joints. | |
container::aligned_vector< Motion > | oa |
Vector of joint accelerations expressed at the origin. | |
container::aligned_vector< Motion > | a_gf |
Vector of joint accelerations due to the gravity field. | |
container::aligned_vector< Motion > | v |
Vector of joint velocities expressed at the centers of the joints. | |
container::aligned_vector< Motion > | ov |
Vector of joint velocities expressed at the origin. | |
container::aligned_vector< Force > | f |
Vector of body forces expressed in the local frame of the joint. For each body, the force represents the sum of all external forces acting on the body. | |
container::aligned_vector< Force > | of |
Vector of body forces expressed in the world frame. For each body, the force represents the sum of all external forces acting on the body. | |
container::aligned_vector< Force > | h |
Vector of spatial momenta expressed in the local frame of the joint. | |
container::aligned_vector< Force > | oh |
Vector of spatial momenta expressed in the world frame. | |
container::aligned_vector< SE3 > | oMi |
Vector of absolute joint placements (wrt the world). | |
container::aligned_vector< SE3 > | liMi |
Vector of relative joint placements (wrt the body parent). | |
Eigen::VectorXd | tau |
Vector of joint torques (dim model.nv). | |
Eigen::VectorXd | nle |
Vector of Non Linear Effects (dim model.nv). It corresponds to concatenation of the Coriolis, centrifugal and gravitational effects. More... | |
Eigen::VectorXd | g |
Vector of generalized gravity (dim model.nv). More... | |
container::aligned_vector< SE3 > | oMf |
Vector of absolute operationnel frame placements (wrt the world). | |
container::aligned_vector< Inertia > | Ycrb |
Vector of sub-tree composite rigid body inertias, i.e. the apparent inertia of the subtree supported by the joint and expressed in the local frame of the joint.. | |
container::aligned_vector< Inertia::Matrix6 > | dYcrb |
Vector of sub-tree composite rigid body inertia time derivatives \( \dot{Y}_{crb}\). See Data::Ycrb for more details. | |
Eigen::MatrixXd | M |
The joint space inertia matrix (a square matrix of dim model.nv). | |
RowMatrixXd | Minv |
The inverse of the joint space inertia matrix (a square matrix of dim model.nv). | |
Eigen::MatrixXd | C |
The Coriolis matrix (a square matrix of dim model.nv). | |
Matrix6x | dFdq |
Variation of the forceset with respect to the joint configuration. | |
Matrix6x | dFdv |
Variation of the forceset with respect to the joint velocity. | |
Matrix6x | dFda |
Variation of the forceset with respect to the joint acceleration. | |
Matrix6x | SDinv |
Used in computeMinverse. | |
Matrix6x | UDinv |
Used in computeMinverse. | |
Matrix6x | IS |
Used in computeMinverse. | |
container::aligned_vector< Inertia::Matrix6 > | vxI |
Right variation of the inertia matrix. | |
container::aligned_vector< Inertia::Matrix6 > | Ivx |
Left variation of the inertia matrix. | |
container::aligned_vector< Inertia > | oYcrb |
Inertia quantities expressed in the world frame. | |
container::aligned_vector< Inertia::Matrix6 > | doYcrb |
Time variation of the inertia quantities expressed in the world frame. | |
Inertia::Matrix6 | Itmp |
Temporary for derivative algorithms. | |
RowMatrix6 | M6tmpR |
Temporary for derivative algorithms. | |
Eigen::VectorXd | ddq |
The joint accelerations computed from ABA. | |
container::aligned_vector< Inertia::Matrix6 > | Yaba |
Inertia matrix of the subtree expressed as dense matrix [ABA]. | |
Eigen::VectorXd | u |
Intermediate quantity corresponding to apparent torque [ABA]. | |
Matrix6x | Ag |
Centroidal Momentum Matrix. More... | |
Matrix6x | dAg |
Centroidal Momentum Matrix Time Variation. More... | |
Force | hg |
Centroidal momentum quantity. More... | |
Inertia | Ig |
Centroidal Composite Rigid Body Inertia. More... | |
container::aligned_vector< Matrix6x > | Fcrb |
Spatial forces set, used in CRBA and CCRBA. | |
std::vector< int > | lastChild |
Index of the last child (for CRBA) | |
std::vector< int > | nvSubtree |
Dimension of the subtree motion space (for CRBA) | |
Eigen::MatrixXd | U |
Joint space intertia matrix square root (upper trianglular part) computed with a Cholesky Decomposition. | |
Eigen::VectorXd | D |
Diagonal of the joint space intertia matrix obtained by a Cholesky Decomposition. | |
Eigen::VectorXd | Dinv |
Diagonal inverse of the joint space intertia matrix obtained by a Cholesky Decomposition. | |
Eigen::VectorXd | tmp |
Temporary of size NV used in Cholesky Decomposition. | |
std::vector< int > | parents_fromRow |
First previous non-zero row in M (used in Cholesky Decomposition). | |
std::vector< int > | nvSubtree_fromRow |
Subtree of the current row index (used in Cholesky Decomposition). | |
Matrix6x | J |
Jacobian of joint placements. More... | |
Matrix6x | dJ |
Derivative of the Jacobian with respect to the time. | |
Matrix6x | dVdq |
Variation of the spatial velocity set with respect to the joint configuration. | |
Matrix6x | dAdq |
Variation of the spatial acceleration set with respect to the joint configuration. | |
Matrix6x | dAdv |
Variation of the spatial acceleration set with respect to the joint velocity. | |
Eigen::MatrixXd | dtau_dq |
Partial derivative of the joint torque vector with respect to the joint configuration. | |
Eigen::MatrixXd | dtau_dv |
Partial derivative of the joint torque vector with respect to the joint velocity. | |
Eigen::MatrixXd | ddq_dq |
Partial derivative of the joint acceleration vector with respect to the joint configuration. | |
Eigen::MatrixXd | ddq_dv |
Partial derivative of the joint acceleration vector with respect to the joint velocity. | |
container::aligned_vector< SE3 > | iMf |
Vector of joint placements wrt to algorithm end effector. | |
container::aligned_vector< Eigen::Vector3d > | com |
Vector of subtree center of mass positions expressed in the root joint of the subtree. In other words, com[j] is the CoM position of the subtree supported by joint \( j \) and expressed in the joint frame \( j \). The element com[0] corresponds to the center of mass position of the whole model and expressed in the global frame. | |
container::aligned_vector< Eigen::Vector3d > | vcom |
Vector of subtree center of mass linear velocities expressed in the root joint of the subtree. In other words, vcom[j] is the CoM linear velocity of the subtree supported by joint \( j \) and expressed in the joint frame \( j \). The element vcom[0] corresponds to the velocity of the CoM of the whole model expressed in the global frame. | |
container::aligned_vector< Eigen::Vector3d > | acom |
Vector of subtree center of mass linear accelerations expressed in the root joint of the subtree. In other words, acom[j] is the CoM linear acceleration of the subtree supported by joint \( j \) and expressed in the joint frame \( j \). The element acom[0] corresponds to the acceleration of the CoM of the whole model expressed in the global frame. | |
std::vector< double > | mass |
Vector of subtree mass. In other words, mass[j] is the mass of the subtree supported by joint \( j \). The element mass[0] corrresponds to the total mass of the model. | |
Matrix3x | Jcom |
Jacobien of center of mass. More... | |
double | kinetic_energy |
Kinetic energy of the model. | |
double | potential_energy |
Potential energy of the model. | |
Eigen::MatrixXd | JMinvJt |
Inverse of the operational-space inertia matrix. | |
Eigen::LLT< Eigen::MatrixXd > | llt_JMinvJt |
Cholesky decompostion of \(\JMinvJt\). | |
Eigen::VectorXd | lambda_c |
Lagrange Multipliers corresponding to the contact forces in se3::forwardDynamics. | |
Eigen::MatrixXd | sDUiJt |
Temporary corresponding to \( \sqrt{D} U^{-1} J^{\top} \). | |
Eigen::VectorXd | torque_residual |
Temporary corresponding to the residual torque \( \tau - b(q,\dot{q}) \). | |
Eigen::VectorXd | dq_after |
Generalized velocity after impact. | |
Eigen::VectorXd | impulse_c |
Lagrange Multipliers corresponding to the contact impulses in se3::impulseDynamics. | |
Matrix3x | staticRegressor |
Default constructor of se3::Data from a se3::Model.
[in] | model | The model structure of the rigid body system. |
Definition at line 35 of file data.hxx.
References Data::a, Data::a_gf, Data::Ag, Data::C, Data::f, Data::Fcrb, Model::gravity, Data::h, se3::idx_v(), Data::J, Data::joints, Model::joints, Data::lastChild, Data::liMi, Data::M, Data::Minv, Model::njoints, Model::nv, se3::nv(), Data::nvSubtree, Data::nvSubtree_fromRow, Data::oa, Data::oMf, Data::oMi, Data::ov, Model::parents, Data::parents_fromRow, Data::U, and Data::v.
Matrix6x Ag |
Centroidal Momentum Matrix.
Definition at line 173 of file data.hpp.
Referenced by se3::ccrba(), se3::checkData(), se3::crbaMinimal(), Data::Data(), and se3::dccrba().
Matrix6x dAg |
Centroidal Momentum Matrix Time Variation.
Definition at line 178 of file data.hpp.
Referenced by se3::dccrba().
Eigen::VectorXd g |
Vector of generalized gravity (dim model.nv).
Definition at line 103 of file data.hpp.
Referenced by se3::computeGeneralizedGravity().
Force hg |
Centroidal momentum quantity.
Definition at line 183 of file data.hpp.
Referenced by se3::ccrba(), and se3::dccrba().
Inertia Ig |
Centroidal Composite Rigid Body Inertia.
Definition at line 187 of file data.hpp.
Referenced by se3::ccrba(), and se3::dccrba().
Matrix6x J |
Jacobian of joint placements.
Definition at line 217 of file data.hpp.
Referenced by JointAccelerationDerivativesBackwardStep< rf >::algo(), se3::checkData(), se3::computeJointJacobians(), Data::Data(), se3::getFrameJacobian(), se3::getJointJacobian(), and se3::jointJacobian().
Matrix3x Jcom |
Jacobien of center of mass.
Definition at line 260 of file data.hpp.
Referenced by se3::checkData(), se3::computeAllTerms(), se3::getJacobianComFromCrba(), and se3::jacobianCenterOfMass().
Eigen::VectorXd nle |
Vector of Non Linear Effects (dim model.nv). It corresponds to concatenation of the Coriolis, centrifugal and gravitational effects.
Definition at line 98 of file data.hpp.
Referenced by se3::checkData(), se3::forwardDynamics(), and se3::nonLinearEffects().