#include <data.hpp>
Public Types | |
enum | { Options = _Options } |
typedef Eigen::Matrix< Scalar, 6, 10, Options > | BodyRegressorType |
The type of the body regressor. More... | |
typedef VectorXs | ConfigVectorType |
Dense vectorized version of a joint configuration vector. More... | |
typedef ForceTpl< Scalar, Options > | Force |
typedef FrameTpl< Scalar, Options > | Frame |
typedef pinocchio::FrameIndex | FrameIndex |
typedef pinocchio::GeomIndex | GeomIndex |
typedef pinocchio::Index | Index |
typedef std::vector< Index > | IndexVector |
typedef InertiaTpl< Scalar, Options > | Inertia |
typedef JointCollectionTpl< Scalar, Options > | JointCollection |
typedef JointDataTpl< Scalar, Options, JointCollectionTpl > | JointData |
typedef pinocchio::JointIndex | JointIndex |
typedef JointModelTpl< Scalar, Options, JointCollectionTpl > | JointModel |
typedef Eigen::Matrix< Scalar, 3, Eigen::Dynamic, Options > | Matrix3x |
The 3d jacobian type (temporary) More... | |
typedef Eigen::Matrix< Scalar, 6, 6, Options > | Matrix6 |
typedef Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > | Matrix6x |
The 6d jacobian type (temporary) More... | |
typedef Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Options > | MatrixXs |
typedef ModelTpl< Scalar, Options, JointCollectionTpl > | Model |
typedef MotionTpl< Scalar, Options > | Motion |
typedef Eigen::Matrix< Scalar, 6, 6, Eigen::RowMajor|Options > | RowMatrix6 |
typedef Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor|Options > | RowMatrixXs |
typedef SE3Tpl< Scalar, Options > | SE3 |
typedef VectorXs | TangentVectorType |
Dense vectorized version of a joint tangent vector (e.g. velocity, acceleration, etc). It also handles the notion of co-tangent vector (e.g. torque, etc). More... | |
typedef Tensor< Scalar, 3, Options > | Tensor3x |
. More... | |
typedef Eigen::Matrix< Scalar, 3, 1, Options > | Vector3 |
typedef Eigen::Matrix< Scalar, Eigen::Dynamic, 1, Options > | VectorXs |
Public Member Functions | |
DataTpl (const Model &model) | |
Default constructor of pinocchio::Data from a pinocchio::Model. More... | |
DataTpl () | |
Default constructor. More... | |
typedef | PINOCCHIO_ALIGNED_STD_VECTOR (JointModel) JointModelVector |
typedef | PINOCCHIO_ALIGNED_STD_VECTOR (JointData) JointDataVector |
PINOCCHIO_ALIGNED_STD_VECTOR (Motion) a | |
Vector of joint accelerations expressed at the centers of the joints frames. More... | |
PINOCCHIO_ALIGNED_STD_VECTOR (Motion) oa | |
Vector of joint accelerations expressed at the origin of the world. More... | |
PINOCCHIO_ALIGNED_STD_VECTOR (Motion) a_gf | |
Vector of joint accelerations due to the gravity field. More... | |
PINOCCHIO_ALIGNED_STD_VECTOR (Motion) oa_gf | |
Vector of joint accelerations expressed at the origin of the world including gravity contribution. More... | |
PINOCCHIO_ALIGNED_STD_VECTOR (Motion) v | |
Vector of joint velocities expressed at the centers of the joints. More... | |
PINOCCHIO_ALIGNED_STD_VECTOR (Motion) ov | |
Vector of joint velocities expressed at the origin. More... | |
PINOCCHIO_ALIGNED_STD_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. More... | |
PINOCCHIO_ALIGNED_STD_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. More... | |
PINOCCHIO_ALIGNED_STD_VECTOR (Force) h | |
Vector of spatial momenta expressed in the local frame of the joint. More... | |
PINOCCHIO_ALIGNED_STD_VECTOR (Force) oh | |
Vector of spatial momenta expressed in the world frame. More... | |
PINOCCHIO_ALIGNED_STD_VECTOR (SE3) oMi | |
Vector of absolute joint placements (wrt the world). More... | |
PINOCCHIO_ALIGNED_STD_VECTOR (SE3) liMi | |
Vector of relative joint placements (wrt the body parent). More... | |
PINOCCHIO_ALIGNED_STD_VECTOR (SE3) oMf | |
Vector of absolute operationnel frame placements (wrt the world). More... | |
PINOCCHIO_ALIGNED_STD_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.. More... | |
PINOCCHIO_ALIGNED_STD_VECTOR (Matrix6) dYcrb | |
Vector of sub-tree composite rigid body inertia time derivatives . See Data::Ycrb for more details. More... | |
PINOCCHIO_ALIGNED_STD_VECTOR (Matrix6) vxI | |
Right variation of the inertia matrix. More... | |
PINOCCHIO_ALIGNED_STD_VECTOR (Matrix6) Ivx | |
Left variation of the inertia matrix. More... | |
PINOCCHIO_ALIGNED_STD_VECTOR (Inertia) oinertias | |
Rigid Body Inertia supported by the joint expressed in the world frame. More... | |
PINOCCHIO_ALIGNED_STD_VECTOR (Inertia) oYcrb | |
Composite Rigid Body Inertia expressed in the world frame. More... | |
PINOCCHIO_ALIGNED_STD_VECTOR (Matrix6) doYcrb | |
Time variation of Composite Rigid Body Inertia expressed in the world frame. More... | |
PINOCCHIO_ALIGNED_STD_VECTOR (Matrix6) Yaba | |
Inertia matrix of the subtree expressed as dense matrix [ABA]. More... | |
PINOCCHIO_ALIGNED_STD_VECTOR (Matrix6x) Fcrb | |
Spatial forces set, used in CRBA and CCRBA. More... | |
PINOCCHIO_ALIGNED_STD_VECTOR (SE3) iMf | |
Vector of joint placements wrt to algorithm end effector. More... | |
PINOCCHIO_ALIGNED_STD_VECTOR (Vector3) 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 and expressed in the joint frame . The element com[0] corresponds to the center of mass position of the whole model and expressed in the global frame. More... | |
PINOCCHIO_ALIGNED_STD_VECTOR (Vector3) 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 and expressed in the joint frame . The element vcom[0] corresponds to the velocity of the CoM of the whole model expressed in the global frame. More... | |
PINOCCHIO_ALIGNED_STD_VECTOR (Vector3) 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 and expressed in the joint frame . The element acom[0] corresponds to the acceleration of the CoM of the whole model expressed in the global frame. More... | |
Public Member Functions inherited from pinocchio::serialization::Serializable< DataTpl< _Scalar, _Options, JointCollectionTpl > > | |
void | loadFromBinary (const std::string &filename) |
Loads a Derived object from an binary file. More... | |
void | loadFromBinary (boost::asio::streambuf &container) |
Loads a Derived object from a binary container. More... | |
void | loadFromBinary (StaticBuffer &container) |
Loads a Derived object from a static binary container. More... | |
void | loadFromString (const std::string &str) |
Loads a Derived object from a string. More... | |
void | loadFromStringStream (std::istringstream &is) |
Loads a Derived object from a stream string. More... | |
void | loadFromText (const std::string &filename) |
Loads a Derived object from a text file. More... | |
void | loadFromXML (const std::string &filename, const std::string &tag_name) |
Loads a Derived object from an XML file. More... | |
void | saveToBinary (const std::string &filename) const |
Saves a Derived object as an binary file. More... | |
void | saveToBinary (boost::asio::streambuf &container) const |
Saves a Derived object as a binary container. More... | |
void | saveToBinary (StaticBuffer &container) const |
Saves a Derived object as a static binary container. More... | |
std::string | saveToString () const |
Saves a Derived object to a string. More... | |
void | saveToStringStream (std::stringstream &ss) const |
Saves a Derived object to a string stream. More... | |
void | saveToText (const std::string &filename) const |
Saves a Derived object as a text file. More... | |
void | saveToXML (const std::string &filename, const std::string &tag_name) const |
Saves a Derived object as an XML file. More... | |
Public Attributes | |
Matrix6x | Ag |
Centroidal Momentum Matrix. More... | |
BodyRegressorType | bodyRegressor |
Body regressor. More... | |
MatrixXs | C |
The Coriolis matrix (a square matrix of dim model.nv). More... | |
VectorXs | D |
Diagonal of the joint space intertia matrix obtained by a Cholesky Decomposition. More... | |
Matrix6x | dAdq |
Variation of the spatial acceleration set with respect to the joint configuration. More... | |
Matrix6x | dAdv |
Variation of the spatial acceleration set with respect to the joint velocity. More... | |
Matrix6x | dAg |
Centroidal Momentum Matrix Time Variation. More... | |
TangentVectorType | ddq |
The joint accelerations computed from ABA. More... | |
MatrixXs | ddq_dq |
Partial derivative of the joint acceleration vector with respect to the joint configuration. More... | |
MatrixXs | ddq_dv |
Partial derivative of the joint acceleration vector with respect to the joint velocity. More... | |
Matrix6x | dFda |
Variation of the forceset with respect to the joint acceleration. More... | |
Matrix6x | dFdq |
Variation of the forceset with respect to the joint configuration. More... | |
Matrix6x | dFdv |
Variation of the forceset with respect to the joint velocity. More... | |
Matrix6x | dHdq |
Variation of the spatial momenta with respect to the joint configuration. More... | |
Force | dhg |
Centroidal momentum time derivative. More... | |
VectorXs | Dinv |
Diagonal inverse of the joint space intertia matrix obtained by a Cholesky Decomposition. More... | |
Matrix6x | dJ |
Derivative of the Jacobian with respect to the time. More... | |
TangentVectorType | dq_after |
Generalized velocity after impact. More... | |
MatrixXs | dtau_dq |
Partial derivative of the joint torque vector with respect to the joint configuration. More... | |
MatrixXs | dtau_dv |
Partial derivative of the joint torque vector with respect to the joint velocity. More... | |
Matrix6x | dVdq |
Variation of the spatial velocity set with respect to the joint configuration. More... | |
std::vector< int > | end_idx_v_fromRow |
End index of the Joint motion subspace. More... | |
VectorXs | g |
Vector of generalized gravity (dim model.nv). More... | |
Force | hg |
Centroidal momentum quantity. More... | |
Inertia | Ig |
Centroidal Composite Rigid Body Inertia. More... | |
VectorXs | impulse_c |
Lagrange Multipliers corresponding to the contact impulses in pinocchio::impulseDynamics. More... | |
Matrix6x | IS |
Used in computeMinverse. More... | |
Matrix6 | Itmp |
Temporary for derivative algorithms. More... | |
Matrix6x | J |
Jacobian of joint placements. More... | |
Matrix3x | Jcom |
Jacobian of center of mass. More... | |
MatrixXs | JMinvJt |
Inverse of the operational-space inertia matrix. More... | |
JointDataVector | joints |
Vector of pinocchio::JointData associated to the pinocchio::JointModel stored in model, encapsulated in JointDataAccessor. More... | |
MatrixXs | jointTorqueRegressor |
Matrix related to joint torque regressor. More... | |
Tensor3x | kinematic_hessians |
Tensor containing the kinematic Hessian of all the joints. More... | |
Scalar | kinetic_energy |
Kinetic energy of the model. More... | |
VectorXs | lambda_c |
Lagrange Multipliers corresponding to the contact forces in pinocchio::forwardDynamics. More... | |
std::vector< int > | lastChild |
Index of the last child (for CRBA) More... | |
Eigen::LLT< MatrixXs > | llt_JMinvJt |
Cholesky decompostion of . More... | |
MatrixXs | M |
The joint space inertia matrix (a square matrix of dim model.nv). More... | |
Matrix6 | M6tmp |
Temporary for derivative algorithms. More... | |
RowMatrix6 | M6tmpR |
RowMatrix6 | M6tmpR2 |
std::vector< Scalar > | mass |
Vector of subtree mass. In other words, mass[j] is the mass of the subtree supported by joint . The element mass[0] corresponds to the total mass of the model. More... | |
RowMatrixXs | Minv |
The inverse of the joint space inertia matrix (a square matrix of dim model.nv). More... | |
VectorXs | nle |
Vector of Non Linear Effects (dim model.nv). It corresponds to concatenation of the Coriolis, centrifugal and gravitational effects. More... | |
std::vector< int > | nvSubtree |
Dimension of the subtree motion space (for CRBA) More... | |
std::vector< int > | nvSubtree_fromRow |
Subtree of the current row index (used in Cholesky Decomposition). More... | |
std::vector< int > | parents_fromRow |
First previous non-zero row in M (used in Cholesky Decomposition). More... | |
Scalar | potential_energy |
Potential energy of the model. More... | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar | Scalar |
Matrix6x | SDinv |
Used in computeMinverse. More... | |
MatrixXs | sDUiJt |
Temporary corresponding to . More... | |
std::vector< int > | start_idx_v_fromRow |
Starting index of the Joint motion subspace. More... | |
Matrix3x | staticRegressor |
Matrix related to static regressor. More... | |
std::vector< std::vector< int > > | supports_fromRow |
Each element of this vector corresponds to the ordered list of indexes belonging to the supporting tree of the given index at the row level. It may be helpful to retrieve the sparsity pattern through it. More... | |
TangentVectorType | tau |
Vector of joint torques (dim model.nv). More... | |
VectorXs | tmp |
Temporary of size NV used in Cholesky Decomposition. More... | |
VectorXs | torque_residual |
Temporary corresponding to the residual torque . More... | |
TangentVectorType | u |
Intermediate quantity corresponding to apparent torque [ABA]. More... | |
MatrixXs | U |
Joint space intertia matrix square root (upper trianglular part) computed with a Cholesky Decomposition. More... | |
Matrix6x | UDinv |
Used in computeMinverse. More... | |
Private Member Functions | |
void | computeLastChild (const Model &model) |
void | computeParents_fromRow (const Model &model) |
void | computeSupports_fromRow (const Model &model) |
Definition at line 29 of file src/multibody/data.hpp.
typedef Eigen::Matrix<Scalar,6,10,Options> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::BodyRegressorType |
The type of the body regressor.
Definition at line 80 of file src/multibody/data.hpp.
typedef VectorXs pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::ConfigVectorType |
Dense vectorized version of a joint configuration vector.
Definition at line 64 of file src/multibody/data.hpp.
typedef ForceTpl<Scalar,Options> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::Force |
Definition at line 43 of file src/multibody/data.hpp.
typedef FrameTpl<Scalar,Options> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::Frame |
Definition at line 45 of file src/multibody/data.hpp.
typedef pinocchio::FrameIndex pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::FrameIndex |
Definition at line 50 of file src/multibody/data.hpp.
typedef pinocchio::GeomIndex pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::GeomIndex |
Definition at line 49 of file src/multibody/data.hpp.
typedef pinocchio::Index pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::Index |
Definition at line 47 of file src/multibody/data.hpp.
typedef std::vector<Index> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::IndexVector |
Definition at line 51 of file src/multibody/data.hpp.
typedef InertiaTpl<Scalar,Options> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::Inertia |
Definition at line 44 of file src/multibody/data.hpp.
typedef JointCollectionTpl<Scalar,Options> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::JointCollection |
Definition at line 37 of file src/multibody/data.hpp.
typedef JointDataTpl<Scalar,Options,JointCollectionTpl> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::JointData |
Definition at line 54 of file src/multibody/data.hpp.
typedef pinocchio::JointIndex pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::JointIndex |
Definition at line 48 of file src/multibody/data.hpp.
typedef JointModelTpl<Scalar,Options,JointCollectionTpl> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::JointModel |
Definition at line 53 of file src/multibody/data.hpp.
typedef Eigen::Matrix<Scalar,3,Eigen::Dynamic,Options> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::Matrix3x |
The 3d jacobian type (temporary)
Definition at line 73 of file src/multibody/data.hpp.
typedef Eigen::Matrix<Scalar,6,6,Options> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::Matrix6 |
Definition at line 75 of file src/multibody/data.hpp.
typedef Eigen::Matrix<Scalar,6,Eigen::Dynamic,Options> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::Matrix6x |
The 6d jacobian type (temporary)
Definition at line 71 of file src/multibody/data.hpp.
typedef Eigen::Matrix<Scalar,Eigen::Dynamic,Eigen::Dynamic,Options> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::MatrixXs |
Definition at line 59 of file src/multibody/data.hpp.
typedef ModelTpl<Scalar,Options,JointCollectionTpl> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::Model |
Definition at line 39 of file src/multibody/data.hpp.
typedef MotionTpl<Scalar,Options> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::Motion |
Definition at line 42 of file src/multibody/data.hpp.
typedef Eigen::Matrix<Scalar,6,6,Eigen::RowMajor | Options> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::RowMatrix6 |
Definition at line 76 of file src/multibody/data.hpp.
typedef Eigen::Matrix<Scalar,Eigen::Dynamic,Eigen::Dynamic,Eigen::RowMajor | Options> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::RowMatrixXs |
Definition at line 77 of file src/multibody/data.hpp.
typedef SE3Tpl<Scalar,Options> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::SE3 |
Definition at line 41 of file src/multibody/data.hpp.
typedef VectorXs pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::TangentVectorType |
Dense vectorized version of a joint tangent vector (e.g. velocity, acceleration, etc). It also handles the notion of co-tangent vector (e.g. torque, etc).
Definition at line 68 of file src/multibody/data.hpp.
typedef Tensor<Scalar,3,Options> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::Tensor3x |
.
The type of Tensor for Kinematics and Dynamics second order derivatives
Definition at line 83 of file src/multibody/data.hpp.
typedef Eigen::Matrix<Scalar,3,1,Options> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::Vector3 |
Definition at line 61 of file src/multibody/data.hpp.
typedef Eigen::Matrix<Scalar,Eigen::Dynamic,1,Options> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::VectorXs |
Definition at line 60 of file src/multibody/data.hpp.
anonymous enum |
Enumerator | |
---|---|
Options |
Definition at line 35 of file src/multibody/data.hpp.
|
explicit |
Default constructor of pinocchio::Data from a pinocchio::Model.
[in] | model | The model structure of the rigid body system. |
|
inline |
Default constructor.
Definition at line 374 of file src/multibody/data.hpp.
|
private |
|
private |
|
private |
typedef pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR | ( | JointModel | ) |
typedef pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR | ( | JointData | ) |
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR | ( | Motion | ) |
Vector of joint accelerations expressed at the centers of the joints frames.
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR | ( | Motion | ) |
Vector of joint accelerations expressed at the origin of the world.
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR | ( | Motion | ) |
Vector of joint accelerations due to the gravity field.
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR | ( | Motion | ) |
Vector of joint accelerations expressed at the origin of the world including gravity contribution.
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR | ( | Motion | ) |
Vector of joint velocities expressed at the centers of the joints.
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR | ( | Motion | ) |
Vector of joint velocities expressed at the origin.
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR | ( | Force | ) |
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.
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR | ( | Force | ) |
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.
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR | ( | Force | ) |
Vector of spatial momenta expressed in the local frame of the joint.
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR | ( | Force | ) |
Vector of spatial momenta expressed in the world frame.
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR | ( | SE3 | ) |
Vector of absolute joint placements (wrt the world).
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR | ( | SE3 | ) |
Vector of relative joint placements (wrt the body parent).
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR | ( | SE3 | ) |
Vector of absolute operationnel frame placements (wrt the world).
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR | ( | Inertia | ) |
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..
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR | ( | Matrix6 | ) |
Vector of sub-tree composite rigid body inertia time derivatives . See Data::Ycrb for more details.
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR | ( | Matrix6 | ) |
Right variation of the inertia matrix.
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR | ( | Matrix6 | ) |
Left variation of the inertia matrix.
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR | ( | Inertia | ) |
Rigid Body Inertia supported by the joint expressed in the world frame.
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR | ( | Inertia | ) |
Composite Rigid Body Inertia expressed in the world frame.
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR | ( | Matrix6 | ) |
Time variation of Composite Rigid Body Inertia expressed in the world frame.
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR | ( | Matrix6 | ) |
Inertia matrix of the subtree expressed as dense matrix [ABA].
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR | ( | Matrix6x | ) |
Spatial forces set, used in CRBA and CCRBA.
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR | ( | SE3 | ) |
Vector of joint placements wrt to algorithm end effector.
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR | ( | Vector3 | ) |
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 and expressed in the joint frame . The element com[0] corresponds to the center of mass position of the whole model and expressed in the global frame.
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR | ( | Vector3 | ) |
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 and expressed in the joint frame . The element vcom[0] corresponds to the velocity of the CoM of the whole model expressed in the global frame.
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR | ( | Vector3 | ) |
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 and expressed in the joint frame . The element acom[0] corresponds to the acceleration of the CoM of the whole model expressed in the global frame.
Matrix6x pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::Ag |
Centroidal Momentum Matrix.
Definition at line 216 of file src/multibody/data.hpp.
BodyRegressorType pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::bodyRegressor |
Body regressor.
Definition at line 356 of file src/multibody/data.hpp.
MatrixXs pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::C |
The Coriolis matrix (a square matrix of dim model.nv).
Definition at line 157 of file src/multibody/data.hpp.
VectorXs pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::D |
Diagonal of the joint space intertia matrix obtained by a Cholesky Decomposition.
Definition at line 258 of file src/multibody/data.hpp.
Matrix6x pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::dAdq |
Variation of the spatial acceleration set with respect to the joint configuration.
Definition at line 287 of file src/multibody/data.hpp.
Matrix6x pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::dAdv |
Variation of the spatial acceleration set with respect to the joint velocity.
Definition at line 290 of file src/multibody/data.hpp.
Matrix6x pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::dAg |
Centroidal Momentum Matrix Time Variation.
Definition at line 221 of file src/multibody/data.hpp.
TangentVectorType pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::ddq |
The joint accelerations computed from ABA.
Definition at line 204 of file src/multibody/data.hpp.
MatrixXs pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::ddq_dq |
Partial derivative of the joint acceleration vector with respect to the joint configuration.
Definition at line 299 of file src/multibody/data.hpp.
MatrixXs pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::ddq_dv |
Partial derivative of the joint acceleration vector with respect to the joint velocity.
Definition at line 302 of file src/multibody/data.hpp.
Matrix6x pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::dFda |
Variation of the forceset with respect to the joint acceleration.
Definition at line 169 of file src/multibody/data.hpp.
Matrix6x pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::dFdq |
Variation of the forceset with respect to the joint configuration.
Definition at line 163 of file src/multibody/data.hpp.
Matrix6x pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::dFdv |
Variation of the forceset with respect to the joint velocity.
Definition at line 166 of file src/multibody/data.hpp.
Matrix6x pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::dHdq |
Variation of the spatial momenta with respect to the joint configuration.
Definition at line 160 of file src/multibody/data.hpp.
Force pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::dhg |
Centroidal momentum time derivative.
Definition at line 233 of file src/multibody/data.hpp.
VectorXs pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::Dinv |
Diagonal inverse of the joint space intertia matrix obtained by a Cholesky Decomposition.
Definition at line 261 of file src/multibody/data.hpp.
Matrix6x pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::dJ |
Derivative of the Jacobian with respect to the time.
Definition at line 281 of file src/multibody/data.hpp.
TangentVectorType pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::dq_after |
Generalized velocity after impact.
Definition at line 347 of file src/multibody/data.hpp.
MatrixXs pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::dtau_dq |
Partial derivative of the joint torque vector with respect to the joint configuration.
Definition at line 293 of file src/multibody/data.hpp.
MatrixXs pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::dtau_dv |
Partial derivative of the joint torque vector with respect to the joint velocity.
Definition at line 296 of file src/multibody/data.hpp.
Matrix6x pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::dVdq |
Variation of the spatial velocity set with respect to the joint configuration.
Definition at line 284 of file src/multibody/data.hpp.
std::vector<int> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::end_idx_v_fromRow |
End index of the Joint motion subspace.
Definition at line 252 of file src/multibody/data.hpp.
VectorXs pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::g |
Vector of generalized gravity (dim model.nv).
Definition at line 138 of file src/multibody/data.hpp.
Force pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::hg |
Centroidal momentum quantity.
Definition at line 227 of file src/multibody/data.hpp.
Inertia pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::Ig |
Centroidal Composite Rigid Body Inertia.
Definition at line 237 of file src/multibody/data.hpp.
VectorXs pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::impulse_c |
Lagrange Multipliers corresponding to the contact impulses in pinocchio::impulseDynamics.
Definition at line 350 of file src/multibody/data.hpp.
Matrix6x pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::IS |
Used in computeMinverse.
Definition at line 178 of file src/multibody/data.hpp.
Matrix6 pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::Itmp |
Temporary for derivative algorithms.
Definition at line 196 of file src/multibody/data.hpp.
Matrix6x pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::J |
Jacobian of joint placements.
Definition at line 278 of file src/multibody/data.hpp.
Matrix3x pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::Jcom |
Jacobian of center of mass.
Definition at line 321 of file src/multibody/data.hpp.
MatrixXs pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::JMinvJt |
Inverse of the operational-space inertia matrix.
Definition at line 332 of file src/multibody/data.hpp.
JointDataVector pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::joints |
Vector of pinocchio::JointData associated to the pinocchio::JointModel stored in model, encapsulated in JointDataAccessor.
Definition at line 87 of file src/multibody/data.hpp.
MatrixXs pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::jointTorqueRegressor |
Matrix related to joint torque regressor.
Definition at line 359 of file src/multibody/data.hpp.
Tensor3x pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::kinematic_hessians |
Tensor containing the kinematic Hessian of all the joints.
Definition at line 362 of file src/multibody/data.hpp.
Scalar pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::kinetic_energy |
Kinetic energy of the model.
Definition at line 324 of file src/multibody/data.hpp.
VectorXs pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::lambda_c |
Lagrange Multipliers corresponding to the contact forces in pinocchio::forwardDynamics.
Definition at line 338 of file src/multibody/data.hpp.
std::vector<int> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::lastChild |
Index of the last child (for CRBA)
Definition at line 243 of file src/multibody/data.hpp.
Eigen::LLT<MatrixXs> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::llt_JMinvJt |
Cholesky decompostion of .
Definition at line 335 of file src/multibody/data.hpp.
MatrixXs pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::M |
The joint space inertia matrix (a square matrix of dim model.nv).
Definition at line 151 of file src/multibody/data.hpp.
Matrix6 pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::M6tmp |
Temporary for derivative algorithms.
Definition at line 199 of file src/multibody/data.hpp.
RowMatrix6 pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::M6tmpR |
Definition at line 200 of file src/multibody/data.hpp.
RowMatrix6 pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::M6tmpR2 |
Definition at line 201 of file src/multibody/data.hpp.
std::vector<Scalar> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::mass |
Vector of subtree mass. In other words, mass[j] is the mass of the subtree supported by joint . The element mass[0] corresponds to the total mass of the model.
Definition at line 317 of file src/multibody/data.hpp.
RowMatrixXs pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::Minv |
The inverse of the joint space inertia matrix (a square matrix of dim model.nv).
Definition at line 154 of file src/multibody/data.hpp.
VectorXs pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::nle |
Vector of Non Linear Effects (dim model.nv). It corresponds to concatenation of the Coriolis, centrifugal and gravitational effects.
Definition at line 133 of file src/multibody/data.hpp.
std::vector<int> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::nvSubtree |
Dimension of the subtree motion space (for CRBA)
Definition at line 246 of file src/multibody/data.hpp.
std::vector<int> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::nvSubtree_fromRow |
Subtree of the current row index (used in Cholesky Decomposition).
Definition at line 274 of file src/multibody/data.hpp.
std::vector<int> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::parents_fromRow |
First previous non-zero row in M (used in Cholesky Decomposition).
Definition at line 267 of file src/multibody/data.hpp.
Scalar pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::potential_energy |
Potential energy of the model.
Definition at line 327 of file src/multibody/data.hpp.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::Scalar |
Definition at line 34 of file src/multibody/data.hpp.
Matrix6x pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::SDinv |
Used in computeMinverse.
Definition at line 172 of file src/multibody/data.hpp.
MatrixXs pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::sDUiJt |
Temporary corresponding to .
Definition at line 341 of file src/multibody/data.hpp.
std::vector<int> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::start_idx_v_fromRow |
Starting index of the Joint motion subspace.
Definition at line 249 of file src/multibody/data.hpp.
Matrix3x pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::staticRegressor |
Matrix related to static regressor.
Definition at line 353 of file src/multibody/data.hpp.
std::vector< std::vector<int> > pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::supports_fromRow |
Each element of this vector corresponds to the ordered list of indexes belonging to the supporting tree of the given index at the row level. It may be helpful to retrieve the sparsity pattern through it.
Definition at line 271 of file src/multibody/data.hpp.
TangentVectorType pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::tau |
Vector of joint torques (dim model.nv).
Definition at line 128 of file src/multibody/data.hpp.
VectorXs pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::tmp |
Temporary of size NV used in Cholesky Decomposition.
Definition at line 264 of file src/multibody/data.hpp.
VectorXs pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::torque_residual |
Temporary corresponding to the residual torque .
Definition at line 344 of file src/multibody/data.hpp.
TangentVectorType pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::u |
Intermediate quantity corresponding to apparent torque [ABA].
Definition at line 211 of file src/multibody/data.hpp.
MatrixXs pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::U |
Joint space intertia matrix square root (upper trianglular part) computed with a Cholesky Decomposition.
Definition at line 255 of file src/multibody/data.hpp.
Matrix6x pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::UDinv |
Used in computeMinverse.
Definition at line 175 of file src/multibody/data.hpp.