#include <generic.hpp>
Public Types | |
enum | { Options = _Options } |
typedef std::map< std::string, ConfigVectorType > | ConfigVectorMap |
Map between a string (key) and a configuration vector. More... | |
typedef VectorXs | ConfigVectorType |
Dense vectorized version of a joint configuration vector. More... | |
typedef DataTpl< Scalar, Options, JointCollectionTpl > | Data |
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 MotionTpl< Scalar, Options > | Motion |
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 Eigen::Matrix< Scalar, 3, 1, Options > | Vector3 |
typedef Eigen::Matrix< Scalar, Eigen::Dynamic, 1, Options > | VectorXs |
Public Member Functions | |
FrameIndex | addBodyFrame (const std::string &body_name, const JointIndex &parentJoint, const SE3 &body_placement=SE3::Identity(), int parentFrame=-1) |
Add a body to the frame tree. More... | |
FrameIndex | addFrame (const Frame &frame, const bool append_inertia=true) |
Adds a frame to the kinematic tree. The inertia stored within the frame will be happened to the inertia supported by the joint (frame.parentJoint). More... | |
JointIndex | addJoint (const JointIndex parent, const JointModel &joint_model, const SE3 &joint_placement, const std::string &joint_name) |
Add a joint to the kinematic tree with infinite bounds. More... | |
JointIndex | addJoint (const JointIndex parent, const JointModel &joint_model, const SE3 &joint_placement, const std::string &joint_name, const VectorXs &max_effort, const VectorXs &max_velocity, const VectorXs &min_config, const VectorXs &max_config) |
JointIndex | addJoint (const JointIndex parent, const JointModel &joint_model, const SE3 &joint_placement, const std::string &joint_name, const VectorXs &max_effort, const VectorXs &max_velocity, const VectorXs &min_config, const VectorXs &max_config, const VectorXs &friction, const VectorXs &damping) |
FrameIndex | addJointFrame (const JointIndex &joint_index, int previous_frame_index=-1) |
Add a joint to the frame tree. More... | |
void | appendBodyToJoint (const JointIndex joint_index, const Inertia &Y, const SE3 &body_placement=SE3::Identity()) |
Append a body to a given joint of the kinematic tree. More... | |
template<typename NewScalar > | |
CastType< NewScalar, ModelTpl >::type | cast () const |
bool | check () const |
Run check(fusion::list) with DEFAULT_CHECKERS as argument. More... | |
template<typename D > | |
bool | check (const AlgorithmCheckerBase< D > &checker=AlgorithmCheckerBase< D >()) const |
Check the validity of the attributes of Model with respect to the specification of some algorithms. More... | |
bool | check (const Data &data) const |
Run checkData on data and current model. More... | |
bool | existBodyName (const std::string &name) const |
Check if a body given by its name exists. More... | |
bool | existFrame (const std::string &name, const FrameType &type=(FrameType)(JOINT|FIXED_JOINT|BODY|OP_FRAME|SENSOR)) const |
Checks if a frame given by its name exists. More... | |
bool | existJointName (const std::string &name) const |
Check if a joint given by its name exists. More... | |
FrameIndex | getBodyId (const std::string &name) const |
Return the index of a body given by its name. More... | |
FrameIndex | getFrameId (const std::string &name, const FrameType &type=(FrameType)(JOINT|FIXED_JOINT|BODY|OP_FRAME|SENSOR)) const |
Returns the index of a frame given by its name. More... | |
JointIndex | getJointId (const std::string &name) const |
Return the index of a joint given by its name. More... | |
std::vector< bool > | hasConfigurationLimit () |
Check if joints have configuration limits. More... | |
std::vector< bool > | hasConfigurationLimitInTangent () |
Check if joints have configuration limits. More... | |
ModelTpl () | |
Default constructor. Builds an empty model with no joints. More... | |
template<typename S2 , int O2> | |
ModelTpl (const ModelTpl< S2, O2 > &other) | |
Copy constructor by casting. More... | |
bool | operator!= (const ModelTpl &other) const |
bool | operator== (const ModelTpl &other) const |
Equality comparison operator. More... | |
typedef | PINOCCHIO_ALIGNED_STD_VECTOR (Frame) FrameVector |
typedef | PINOCCHIO_ALIGNED_STD_VECTOR (Inertia) InertiaVector |
typedef | PINOCCHIO_ALIGNED_STD_VECTOR (JointData) JointDataVector |
typedef | PINOCCHIO_ALIGNED_STD_VECTOR (JointModel) JointModelVector |
typedef | PINOCCHIO_ALIGNED_STD_VECTOR (SE3) SE3Vector |
Public Attributes | |
VectorXs | armature |
Vector of armature values expressed at the joint level This vector may contain the contribution of rotor inertia effects for instance. More... | |
std::vector< IndexVector > | children |
Vector of children index. Chidren of the i*th joint, denoted *mu(i) corresponds to the set (i==parents[k] for k in mu(i)). More... | |
TangentVectorType | damping |
Vector of joint damping parameters. More... | |
TangentVectorType | effortLimit |
Vector of maximal joint torques. More... | |
FrameVector | frames |
Vector of operational frames registered on the model. More... | |
TangentVectorType | friction |
Vector of joint friction parameters. More... | |
Motion | gravity |
Spatial gravity of the model. More... | |
std::vector< int > | idx_qs |
Vector of starting index of the *i*th joint in the configuration space. More... | |
std::vector< int > | idx_vs |
Starting index of the *i*th joint in the tangent configuration space. More... | |
InertiaVector | inertias |
Vector of spatial inertias supported by each joint. More... | |
SE3Vector | jointPlacements |
Vector of joint placements: placement of a joint i wrt its parent joint frame. More... | |
JointModelVector | joints |
Vector of joint models. More... | |
ConfigVectorType | lowerPositionLimit |
Lower joint configuration limit. More... | |
std::string | name |
Model name. More... | |
std::vector< std::string > | names |
Name of the joints. More... | |
int | nbodies |
Number of bodies. More... | |
int | nframes |
Number of operational frames. More... | |
int | njoints |
Number of joints. More... | |
int | nq |
Dimension of the configuration vector representation. More... | |
std::vector< int > | nqs |
Vector of dimension of the joint configuration subspace. More... | |
int | nv |
Dimension of the velocity vector space. More... | |
std::vector< int > | nvs |
Dimension of the *i*th joint tangent subspace. More... | |
std::vector< JointIndex > | parents |
Vector of parent joint indexes. The parent of joint i, denoted li, corresponds to li==parents[i]. More... | |
ConfigVectorMap | referenceConfigurations |
Map of reference configurations, indexed by user given names. More... | |
TangentVectorType | rotorGearRatio |
Vector of rotor gear ratio parameters. More... | |
TangentVectorType | rotorInertia |
Vector of rotor inertia parameters. More... | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar | Scalar |
std::vector< IndexVector > | subtrees |
Vector of joint subtrees. subtree[j] corresponds to the subtree supported by the joint j. The first element of subtree[j] is the index of the joint j itself. More... | |
std::vector< IndexVector > | supports |
Vector of joint supports. supports[j] corresponds to the vector of indices of the joints located on the path between joint j and "universe". The first element of supports[j] is "universe", the last one is the index of joint j itself. More... | |
ConfigVectorType | upperPositionLimit |
Upper joint configuration limit. More... | |
TangentVectorType | velocityLimit |
Vector of maximal joint velocities. More... | |
Static Public Attributes | |
static const Vector3 | gravity981 |
Default 3D gravity vector (=(0,0,-9.81)). More... | |
Protected Member Functions | |
void | addJointIndexToParentSubtrees (const JointIndex joint_id) |
Add the joint_id to its parent subtrees. More... | |
Definition at line 20 of file context/generic.hpp.
typedef std::map<std::string, ConfigVectorType> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::ConfigVectorMap |
Map between a string (key) and a configuration vector.
Definition at line 90 of file multibody/model.hpp.
typedef VectorXs pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::ConfigVectorType |
Dense vectorized version of a joint configuration vector.
Definition at line 87 of file multibody/model.hpp.
typedef DataTpl<Scalar, Options, JointCollectionTpl> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::Data |
Definition at line 58 of file multibody/model.hpp.
typedef ForceTpl<Scalar, Options> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::Force |
Definition at line 62 of file multibody/model.hpp.
typedef FrameTpl<Scalar, Options> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::Frame |
Definition at line 64 of file multibody/model.hpp.
typedef pinocchio::FrameIndex pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::FrameIndex |
Definition at line 69 of file multibody/model.hpp.
typedef pinocchio::GeomIndex pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::GeomIndex |
Definition at line 68 of file multibody/model.hpp.
typedef pinocchio::Index pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::Index |
Definition at line 66 of file multibody/model.hpp.
typedef std::vector<Index> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::IndexVector |
Definition at line 70 of file multibody/model.hpp.
typedef InertiaTpl<Scalar, Options> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::Inertia |
Definition at line 63 of file multibody/model.hpp.
typedef JointCollectionTpl<Scalar, Options> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::JointCollection |
Definition at line 57 of file multibody/model.hpp.
typedef JointDataTpl<Scalar, Options, JointCollectionTpl> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::JointData |
Definition at line 73 of file multibody/model.hpp.
typedef pinocchio::JointIndex pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::JointIndex |
Definition at line 67 of file multibody/model.hpp.
typedef JointModelTpl<Scalar, Options, JointCollectionTpl> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::JointModel |
Definition at line 72 of file multibody/model.hpp.
typedef MotionTpl<Scalar, Options> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::Motion |
Definition at line 61 of file multibody/model.hpp.
typedef SE3Tpl<Scalar, Options> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::SE3 |
Definition at line 60 of file multibody/model.hpp.
typedef VectorXs pinocchio::ModelTpl< _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 95 of file multibody/model.hpp.
typedef Eigen::Matrix<Scalar, 3, 1, Options> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::Vector3 |
Definition at line 81 of file multibody/model.hpp.
typedef Eigen::Matrix<Scalar, Eigen::Dynamic, 1, Options> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::VectorXs |
Definition at line 80 of file multibody/model.hpp.
anonymous enum |
Enumerator | |
---|---|
Options |
Definition at line 52 of file multibody/model.hpp.
|
inline |
Default constructor. Builds an empty model with no joints.
Definition at line 200 of file multibody/model.hpp.
|
inlineexplicit |
Copy constructor by casting.
[in] | other | model to copy to *this |
Definition at line 233 of file multibody/model.hpp.
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI FrameIndex pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::addBodyFrame | ( | const std::string & | body_name, |
const JointIndex & | parentJoint, | ||
const SE3 & | body_placement = SE3::Identity() , |
||
int | parentFrame = -1 |
||
) |
Add a body to the frame tree.
[in] | body_name | Name of the body. |
[in] | parentJoint | Index of the parent joint. |
[in] | body_placement | The relative placement of the body regarding to the parent joint. Set default to the Identity placement. |
[in] | parentFrame | Index of the parent frame. If negative, the parent frame is the frame of the parent joint. |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI FrameIndex pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::addFrame | ( | const Frame & | frame, |
const bool | append_inertia = true |
||
) |
Adds a frame to the kinematic tree. The inertia stored within the frame will be happened to the inertia supported by the joint (frame.parentJoint).
[in] | frame | The frame to add to the kinematic tree. |
[in] | append_inertia | Append the inertia contained in the Frame to the inertia supported by the joint. |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI JointIndex pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::addJoint | ( | const JointIndex | parent, |
const JointModel & | joint_model, | ||
const SE3 & | joint_placement, | ||
const std::string & | joint_name | ||
) |
Add a joint to the kinematic tree with infinite bounds.
JointModelDerived | The type of the joint model. |
[in] | parent | Index of the parent joint. |
[in] | joint_model | The joint model. |
[in] | joint_placement | Placement of the joint inside its parent joint. |
[in] | joint_name | Name of the joint. If empty, the name is random. |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI JointIndex pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::addJoint | ( | const JointIndex | parent, |
const JointModel & | joint_model, | ||
const SE3 & | joint_placement, | ||
const std::string & | joint_name, | ||
const VectorXs & | max_effort, | ||
const VectorXs & | max_velocity, | ||
const VectorXs & | min_config, | ||
const VectorXs & | max_config | ||
) |
[in] | max_effort | Maximal joint torque. |
[in] | max_velocity | Maximal joint velocity. |
[in] | min_config | Lower joint configuration. |
[in] | max_config | Upper joint configuration. |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI JointIndex pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::addJoint | ( | const JointIndex | parent, |
const JointModel & | joint_model, | ||
const SE3 & | joint_placement, | ||
const std::string & | joint_name, | ||
const VectorXs & | max_effort, | ||
const VectorXs & | max_velocity, | ||
const VectorXs & | min_config, | ||
const VectorXs & | max_config, | ||
const VectorXs & | friction, | ||
const VectorXs & | damping | ||
) |
[in] | friction | Joint friction parameters. |
[in] | damping | Joint damping parameters. |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI FrameIndex pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::addJointFrame | ( | const JointIndex & | joint_index, |
int | previous_frame_index = -1 |
||
) |
Add a joint to the frame tree.
[in] | jointIndex | Index of the joint. |
[in] | frameIndex | Index of the parent frame. If negative, the parent frame is the frame of the parent joint. |
|
protected |
Add the joint_id to its parent subtrees.
[in] | joint_id | The id of the joint to add to the subtrees |
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::appendBodyToJoint | ( | const JointIndex | joint_index, |
const Inertia & | Y, | ||
const SE3 & | body_placement = SE3::Identity() |
||
) |
Append a body to a given joint of the kinematic tree.
[in] | joint_index | Index of the supporting joint. |
[in] | Y | Spatial inertia of the body. |
[in] | body_placement | The relative placement of the body regarding to the parent joint. Set default to the Identity placement. |
CastType<NewScalar, ModelTpl>::type pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::cast | ( | ) | const |
|
inline |
Run check(fusion::list) with DEFAULT_CHECKERS as argument.
Definition at line 23 of file default-check.hpp.
|
inline |
Check the validity of the attributes of Model with respect to the specification of some algorithms.
The method is a template so that the checkers can be defined in each algorithms.
[in] | checker | a class, typically defined in the algorithm module, that validates the attributes of model. |
Definition at line 461 of file multibody/model.hpp.
bool pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::check | ( | const Data & | data | ) | const |
Run checkData on data and current model.
[in] | data | to be checked wrt *this. |
bool pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::existBodyName | ( | const std::string & | name | ) | const |
Check if a body given by its name exists.
[in] | name | Name of the body. |
bool pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::existFrame | ( | const std::string & | name, |
const FrameType & | type = (FrameType)(JOINT|FIXED_JOINT|BODY|OP_FRAME|SENSOR) |
||
) | const |
Checks if a frame given by its name exists.
[in] | name | Name of the frame. |
[in] | type | Type of the frame. |
bool pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::existJointName | ( | const std::string & | name | ) | const |
Check if a joint given by its name exists.
[in] | name | Name of the joint. |
FrameIndex pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::getBodyId | ( | const std::string & | name | ) | const |
Return the index of a body given by its name.
[in] | name | Name of the body. |
FrameIndex pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::getFrameId | ( | const std::string & | name, |
const FrameType & | type = (FrameType)(JOINT|FIXED_JOINT|BODY|OP_FRAME|SENSOR) |
||
) | const |
Returns the index of a frame given by its name.
[in] | name | Name of the frame. |
[in] | type | Type of the frame. |
JointIndex pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::getJointId | ( | const std::string & | name | ) | const |
Return the index of a joint given by its name.
[in] | name | Name of the joint. |
std::vector<bool> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::hasConfigurationLimit | ( | ) |
Check if joints have configuration limits.
std::vector<bool> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::hasConfigurationLimitInTangent | ( | ) |
Check if joints have configuration limits.
|
inline |
Definition at line 252 of file multibody/model.hpp.
bool pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::operator== | ( | const ModelTpl< _Scalar, _Options, JointCollectionTpl > & | other | ) | const |
Equality comparison operator.
typedef pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR | ( | Frame | ) |
typedef pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR | ( | Inertia | ) |
typedef pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR | ( | JointData | ) |
typedef pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR | ( | JointModel | ) |
typedef pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR | ( | SE3 | ) |
VectorXs pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::armature |
Vector of armature values expressed at the joint level This vector may contain the contribution of rotor inertia effects for instance.
Definition at line 149 of file multibody/model.hpp.
std::vector<IndexVector> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::children |
Vector of children index. Chidren of the i*th joint, denoted *mu(i) corresponds to the set (i==parents[k] for k in mu(i)).
Definition at line 139 of file multibody/model.hpp.
TangentVectorType pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::damping |
Vector of joint damping parameters.
Definition at line 161 of file multibody/model.hpp.
TangentVectorType pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::effortLimit |
Vector of maximal joint torques.
Definition at line 164 of file multibody/model.hpp.
FrameVector pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::frames |
Vector of operational frames registered on the model.
Definition at line 176 of file multibody/model.hpp.
TangentVectorType pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::friction |
Vector of joint friction parameters.
Definition at line 158 of file multibody/model.hpp.
Motion pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::gravity |
Spatial gravity of the model.
Definition at line 191 of file multibody/model.hpp.
|
static |
Default 3D gravity vector (=(0,0,-9.81)).
Definition at line 194 of file multibody/model.hpp.
std::vector<int> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::idx_qs |
Vector of starting index of the *i*th joint in the configuration space.
Definition at line 122 of file multibody/model.hpp.
std::vector<int> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::idx_vs |
Starting index of the *i*th joint in the tangent configuration space.
Definition at line 128 of file multibody/model.hpp.
InertiaVector pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::inertias |
Vector of spatial inertias supported by each joint.
Definition at line 113 of file multibody/model.hpp.
SE3Vector pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::jointPlacements |
Vector of joint placements: placement of a joint i wrt its parent joint frame.
Definition at line 116 of file multibody/model.hpp.
JointModelVector pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::joints |
Vector of joint models.
Definition at line 119 of file multibody/model.hpp.
ConfigVectorType pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::lowerPositionLimit |
Lower joint configuration limit.
Definition at line 170 of file multibody/model.hpp.
std::string pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::name |
Model name.
Definition at line 197 of file multibody/model.hpp.
std::vector<std::string> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::names |
Name of the joints.
Definition at line 142 of file multibody/model.hpp.
int pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::nbodies |
Number of bodies.
Definition at line 107 of file multibody/model.hpp.
int pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::nframes |
Number of operational frames.
Definition at line 110 of file multibody/model.hpp.
int pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::njoints |
Number of joints.
Definition at line 104 of file multibody/model.hpp.
int pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::nq |
Dimension of the configuration vector representation.
Definition at line 98 of file multibody/model.hpp.
std::vector<int> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::nqs |
Vector of dimension of the joint configuration subspace.
Definition at line 125 of file multibody/model.hpp.
int pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::nv |
Dimension of the velocity vector space.
Definition at line 101 of file multibody/model.hpp.
std::vector<int> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::nvs |
Dimension of the *i*th joint tangent subspace.
Definition at line 131 of file multibody/model.hpp.
std::vector<JointIndex> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::parents |
Vector of parent joint indexes. The parent of joint i, denoted li, corresponds to li==parents[i].
Definition at line 135 of file multibody/model.hpp.
ConfigVectorMap pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::referenceConfigurations |
Map of reference configurations, indexed by user given names.
Definition at line 145 of file multibody/model.hpp.
TangentVectorType pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::rotorGearRatio |
Vector of rotor gear ratio parameters.
Definition at line 155 of file multibody/model.hpp.
TangentVectorType pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::rotorInertia |
Vector of rotor inertia parameters.
Definition at line 152 of file multibody/model.hpp.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::Scalar |
Definition at line 51 of file multibody/model.hpp.
std::vector<IndexVector> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::subtrees |
Vector of joint subtrees. subtree[j] corresponds to the subtree supported by the joint j. The first element of subtree[j] is the index of the joint j itself.
Definition at line 188 of file multibody/model.hpp.
std::vector<IndexVector> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::supports |
Vector of joint supports. supports[j] corresponds to the vector of indices of the joints located on the path between joint j and "universe". The first element of supports[j] is "universe", the last one is the index of joint j itself.
Definition at line 183 of file multibody/model.hpp.
ConfigVectorType pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::upperPositionLimit |
Upper joint configuration limit.
Definition at line 173 of file multibody/model.hpp.
TangentVectorType pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::velocityLimit |
Vector of maximal joint velocities.
Definition at line 167 of file multibody/model.hpp.