Public Types | Public Member Functions | Public Attributes | Static Public Attributes | Protected Member Functions | List of all members
pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl > Struct Template Reference

#include <fwd.hpp>

Inheritance diagram for pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >:
Inheritance graph
[legend]

Public Types

enum  { Options = _Options }
 
typedef std::map< std::string, ConfigVectorTypeConfigVectorMap
 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, OptionsForce
 
typedef FrameTpl< Scalar, OptionsFrame
 
typedef pinocchio::FrameIndex FrameIndex
 
typedef pinocchio::GeomIndex GeomIndex
 
typedef pinocchio::Index Index
 
typedef std::vector< IndexIndexVector
 
typedef InertiaTpl< Scalar, OptionsInertia
 
typedef JointCollectionTpl< Scalar, OptionsJointCollection
 
typedef JointDataTpl< Scalar, Options, JointCollectionTpl > JointData
 
typedef pinocchio::JointIndex JointIndex
 
typedef JointModelTpl< Scalar, Options, JointCollectionTpl > JointModel
 
typedef MotionTpl< Scalar, OptionsMotion
 
typedef SE3Tpl< Scalar, OptionsSE3
 
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, OptionsVector3
 
typedef Eigen::Matrix< Scalar, Eigen::Dynamic, 1, OptionsVectorXs
 

Public Member Functions

FrameIndex addBodyFrame (const std::string &body_name, const JointIndex &parentJoint, const SE3 &body_placement=SE3::Identity(), int previousFrame=-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.parent). 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)
 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, const VectorXs &friction, const VectorXs &damping)
 Add a joint to the kinematic tree with infinite bounds. More...
 
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 >
ModelTpl< NewScalar, Options, JointCollectionTpl > cast () const
 
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
 Run check(fusion::list) with DEFAULT_CHECKERS as argument. 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...
 
 ModelTpl ()
 Default constructor. Builds an empty model with no joints. More...
 
bool operator!= (const ModelTpl &other) const
 
bool operator== (const ModelTpl &other) const
 Equality comparison operator. More...
 
typedef PINOCCHIO_ALIGNED_STD_VECTOR (JointModel) JointModelVector
 
typedef PINOCCHIO_ALIGNED_STD_VECTOR (JointData) JointDataVector
 
typedef PINOCCHIO_ALIGNED_STD_VECTOR (Frame) FrameVector
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Inertia) inertias
 Spatial inertias of the body i expressed in the supporting joint frame i. More...
 
 PINOCCHIO_ALIGNED_STD_VECTOR (SE3) jointPlacements
 Placement (SE3) of the input of joint i regarding to the parent joint output li. More...
 
 ~ModelTpl ()
 
- Public Member Functions inherited from pinocchio::serialization::Serializable< ModelTpl< _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

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
 Starting index of the joint i in the configuration space. More...
 
std::vector< int > idx_vs
 Starting index of the joint i in the tangent configuration space. More...
 
JointModelVector joints
 Model of joint i, encapsulated in a JointModelAccessor. More...
 
ConfigVectorType lowerPositionLimit
 Lower joint configuration limit. More...
 
std::string name
 Model name;. More...
 
std::vector< std::string > names
 Name of joint i 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
 Dimension of the joint i configuration subspace. More...
 
int nv
 Dimension of the velocity vector space. More...
 
std::vector< int > nvs
 Dimension of the joint i tangent subspace. More...
 
std::vector< JointIndexparents
 Joint parent of joint i, denoted li (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< IndexVectorsubtrees
 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< IndexVectorsupports
 Vector of joint supports. supports[j] corresponds to the collection of all joints located on the path between body j and the root. The last element of supports[j] is the index of the 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...
 

Detailed Description

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
struct pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >

Definition at line 23 of file src/multibody/fwd.hpp.

Member Typedef Documentation

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
typedef std::map<std::string, ConfigVectorType> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::ConfigVectorMap

Map between a string (key) and a configuration vector.

Definition at line 69 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
typedef VectorXs pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::ConfigVectorType

Dense vectorized version of a joint configuration vector.

Definition at line 66 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
typedef DataTpl<Scalar,Options,JointCollectionTpl> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::Data

Definition at line 40 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
typedef ForceTpl<Scalar,Options> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::Force

Definition at line 44 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
typedef FrameTpl<Scalar,Options> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::Frame

Definition at line 46 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
typedef pinocchio::FrameIndex pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::FrameIndex

Definition at line 51 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
typedef pinocchio::GeomIndex pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::GeomIndex

Definition at line 50 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
typedef pinocchio::Index pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::Index

Definition at line 48 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
typedef std::vector<Index> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::IndexVector

Definition at line 52 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
typedef InertiaTpl<Scalar,Options> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::Inertia

Definition at line 45 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
typedef JointCollectionTpl<Scalar,Options> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::JointCollection

Definition at line 39 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
typedef JointDataTpl<Scalar,Options,JointCollectionTpl> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::JointData

Definition at line 55 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
typedef pinocchio::JointIndex pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::JointIndex

Definition at line 49 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
typedef JointModelTpl<Scalar,Options,JointCollectionTpl> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::JointModel

Definition at line 54 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
typedef MotionTpl<Scalar,Options> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::Motion

Definition at line 43 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
typedef SE3Tpl<Scalar,Options> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::SE3

Definition at line 42 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
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 73 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
typedef Eigen::Matrix<Scalar,3,1,Options> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::Vector3

Definition at line 63 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
typedef Eigen::Matrix<Scalar,Eigen::Dynamic,1,Options> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::VectorXs

Definition at line 62 of file src/multibody/model.hpp.

Member Enumeration Documentation

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
anonymous enum
Enumerator
Options 

Definition at line 37 of file src/multibody/model.hpp.

Constructor & Destructor Documentation

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::ModelTpl ( )
inline

Default constructor. Builds an empty model with no joints.

Definition at line 167 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::~ModelTpl ( )
inline

Definition at line 192 of file src/multibody/model.hpp.

Member Function Documentation

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
FrameIndex pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::addBodyFrame ( const std::string &  body_name,
const JointIndex parentJoint,
const SE3 body_placement = SE3::Identity(),
int  previousFrame = -1 
)

Add a body to the frame tree.

Parameters
[in]body_nameName of the body.
[in]parentJointIndex of the parent joint.
[in]body_placementThe relative placement of the body regarding to the parent joint. Set default to the Identity placement.
[in]previousFrameIndex of the parent frame. If negative, the parent frame is the frame of the parent joint.
Returns
The index of the new frame
template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
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.parent).

Parameters
[in]frameThe frame to add to the kinematic tree.
[in]append_inertiaAppend the inertia contained in the Frame to the inertia supported by the joint.
Returns
Returns the index of the frame if it has been successfully added or if it already exists in the kinematic tree.
template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
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.

Remarks
This method also adds a Frame of same name to the vector of frames.
The inertia supported by the joint is set to Zero.
Template Parameters
JointModelDerivedThe type of the joint model.
Parameters
[in]parentIndex of the parent joint.
[in]joint_modelThe joint model.
[in]joint_placementPlacement of the joint inside its parent joint.
[in]joint_nameName of the joint. If empty, the name is random.
Returns
The index of the new joint.
See also
Model::appendBodyToJoint
template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
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 
)

Add a joint to the kinematic tree with infinite bounds.

Remarks
This method also adds a Frame of same name to the vector of frames.
The inertia supported by the joint is set to Zero.
Template Parameters
JointModelDerivedThe type of the joint model.
Parameters
[in]parentIndex of the parent joint.
[in]joint_modelThe joint model.
[in]joint_placementPlacement of the joint inside its parent joint.
[in]joint_nameName of the joint. If empty, the name is random.
Returns
The index of the new joint.
See also
Model::appendBodyToJoint
Parameters
[in]max_effortMaximal joint torque.
[in]max_velocityMaximal joint velocity.
[in]min_configLower joint configuration.
[in]max_configUpper joint configuration.
template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
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 
)

Add a joint to the kinematic tree with infinite bounds.

Remarks
This method also adds a Frame of same name to the vector of frames.
The inertia supported by the joint is set to Zero.
Template Parameters
JointModelDerivedThe type of the joint model.
Parameters
[in]parentIndex of the parent joint.
[in]joint_modelThe joint model.
[in]joint_placementPlacement of the joint inside its parent joint.
[in]joint_nameName of the joint. If empty, the name is random.
Returns
The index of the new joint.
See also
Model::appendBodyToJoint
Parameters
[in]max_effortMaximal joint torque.
[in]max_velocityMaximal joint velocity.
[in]min_configLower joint configuration.
[in]max_configUpper joint configuration.
[in]frictionJoint friction parameters.
[in]dampingJoint damping parameters.
template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
FrameIndex pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::addJointFrame ( const JointIndex joint_index,
int  previous_frame_index = -1 
)

Add a joint to the frame tree.

Parameters
[in]jointIndexIndex of the joint.
[in]frameIndexIndex of the parent frame. If negative, the parent frame is the frame of the parent joint.
Returns
The index of the new frame
template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
void pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::addJointIndexToParentSubtrees ( const JointIndex  joint_id)
protected

Add the joint_id to its parent subtrees.

Parameters
[in]joint_idThe id of the joint to add to the subtrees
template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
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.

Parameters
[in]joint_indexIndex of the supporting joint.
[in]YSpatial inertia of the body.
[in]body_placementThe relative placement of the body regarding to the parent joint. Set default to the Identity placement.
See also
Model::addJoint
template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
template<typename NewScalar >
ModelTpl<NewScalar,Options,JointCollectionTpl> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::cast ( ) const
inline
Returns
An expression of *this with the Scalar type casted to NewScalar.

copy into vectors

Definition at line 196 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
template<typename D >
bool pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::check ( const AlgorithmCheckerBase< D > &  checker = AlgorithmCheckerBase<D>()) const
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.

Parameters
[in]checkera class, typically defined in the algorithm module, that validates the attributes of model.
Returns
true if the Model is valid, false otherwise.

Definition at line 549 of file src/multibody/model.hpp.

template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
bool pinocchio::ModelTpl< Scalar, Options, JointCollectionTpl >::check ( ) const
inline

Run check(fusion::list) with DEFAULT_CHECKERS as argument.

Definition at line 21 of file default-check.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
bool pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::check ( const Data data) const
inline

Run checkData on data and current model.

Parameters
[in]datato be checked wrt *this.
Returns
true if the data is valid, false otherwise.
template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
bool pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::existBodyName ( const std::string &  name) const

Check if a body given by its name exists.

Parameters
[in]nameName of the body.
Returns
True if the body exists in the kinematic tree.
template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
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.

Parameters
[in]nameName of the frame.
[in]typeType of the frame.
Returns
Returns true if the frame exists.
template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
bool pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::existJointName ( const std::string &  name) const

Check if a joint given by its name exists.

Parameters
[in]nameName of the joint.
Returns
True if the joint exists in the kinematic tree.
template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
FrameIndex pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::getBodyId ( const std::string &  name) const

Return the index of a body given by its name.

Warning
If no body is found, return the number of elements at time T. This can lead to errors if the model is expanded after this method is called (for example to get the id of a parent body)
Parameters
[in]nameName of the body.
Returns
Index of the body.
template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
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.

See also
Model::existFrame to check if the frame exists or not.
Warning
If no frame is found, returns the size of the vector of Model::frames. This can lead to errors if the model is expanded after this method is called (for example to get the id of a parent frame).
Parameters
[in]nameName of the frame.
[in]typeType of the frame.
Returns
Index of the frame.
template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
JointIndex pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::getJointId ( const std::string &  name) const

Return the index of a joint given by its name.

Warning
If no joint is found, return the number of elements at time T. This can lead to errors if the model is expanded after this method is called (for example to get the id of a parent joint)
Parameters
[in]nameName of the joint.
Returns
Index of the joint.
template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
bool pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::operator!= ( const ModelTpl< _Scalar, _Options, JointCollectionTpl > &  other) const
inline
Returns
true if *this is NOT equal to other.

Definition at line 356 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
bool pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::operator== ( const ModelTpl< _Scalar, _Options, JointCollectionTpl > &  other) const
inline

Equality comparison operator.

Returns
true if *this is equal to other.

Definition at line 259 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
typedef pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR ( JointModel  )
template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
typedef pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR ( JointData  )
template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
typedef pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR ( Frame  )
template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR ( Inertia  )

Spatial inertias of the body i expressed in the supporting joint frame i.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR ( SE3  )

Placement (SE3) of the input of joint i regarding to the parent joint output li.

Member Data Documentation

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
TangentVectorType pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::damping

Vector of joint damping parameters.

Definition at line 130 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
TangentVectorType pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::effortLimit

Vector of maximal joint torques.

Definition at line 133 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
FrameVector pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::frames

Vector of operational frames registered on the model.

Definition at line 145 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
TangentVectorType pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::friction

Vector of joint friction parameters.

Definition at line 127 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
Motion pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::gravity

Spatial gravity of the model.

Definition at line 158 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
const Vector3 pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::gravity981
static

Default 3D gravity vector (=(0,0,-9.81)).

Definition at line 161 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
std::vector<int> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::idx_qs

Starting index of the joint i in the configuration space.

Definition at line 100 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
std::vector<int> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::idx_vs

Starting index of the joint i in the tangent configuration space.

Definition at line 106 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
JointModelVector pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::joints

Model of joint i, encapsulated in a JointModelAccessor.

Definition at line 97 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
ConfigVectorType pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::lowerPositionLimit

Lower joint configuration limit.

Definition at line 139 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
std::string pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::name

Model name;.

Definition at line 164 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
std::vector<std::string> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::names

Name of joint i

Definition at line 115 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
int pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::nbodies

Number of bodies.

Definition at line 85 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
int pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::nframes

Number of operational frames.

Definition at line 88 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
int pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::njoints

Number of joints.

Definition at line 82 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
int pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::nq

Dimension of the configuration vector representation.

Definition at line 76 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
std::vector<int> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::nqs

Dimension of the joint i configuration subspace.

Definition at line 103 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
int pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::nv

Dimension of the velocity vector space.

Definition at line 79 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
std::vector<int> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::nvs

Dimension of the joint i tangent subspace.

Definition at line 109 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
std::vector<JointIndex> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::parents

Joint parent of joint i, denoted li (li==parents[i]).

Definition at line 112 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
ConfigVectorMap pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::referenceConfigurations

Map of reference configurations, indexed by user given names.

Definition at line 118 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
TangentVectorType pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::rotorGearRatio

Vector of rotor gear ratio parameters.

Definition at line 124 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
TangentVectorType pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::rotorInertia

Vector of rotor inertia parameters.

Definition at line 121 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::Scalar

Definition at line 36 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
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 155 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
std::vector<IndexVector> pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::supports

Vector of joint supports. supports[j] corresponds to the collection of all joints located on the path between body j and the root. The last element of supports[j] is the index of the joint j itself.

Definition at line 150 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
ConfigVectorType pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::upperPositionLimit

Upper joint configuration limit.

Definition at line 142 of file src/multibody/model.hpp.

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
TangentVectorType pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >::velocityLimit

Vector of maximal joint velocities.

Definition at line 136 of file src/multibody/model.hpp.


The documentation for this struct was generated from the following files:


pinocchio
Author(s):
autogenerated on Tue Jun 1 2021 02:45:06