Template Struct ModelTpl

Inheritance Relationships

Base Type

Struct Documentation

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

Public Types

Values:

enumerator Options
typedef JointCollectionTpl<Scalar, Options> JointCollection
typedef DataTpl<Scalar, Options, JointCollectionTpl> Data
typedef SE3Tpl<Scalar, Options> SE3
typedef MotionTpl<Scalar, Options> Motion
typedef ForceTpl<Scalar, Options> Force
typedef InertiaTpl<Scalar, Options> Inertia
typedef FrameTpl<Scalar, Options> Frame
typedef pinocchio::Index Index
typedef pinocchio::JointIndex JointIndex
typedef pinocchio::GeomIndex GeomIndex
typedef pinocchio::FrameIndex FrameIndex
typedef std::vector<Index> IndexVector
typedef JointModelTpl<Scalar, Options, JointCollectionTpl> JointModel
typedef JointDataTpl<Scalar, Options, JointCollectionTpl> JointData
typedef Eigen::Matrix<Scalar, Eigen::Dynamic, 1, Options> VectorXs
typedef Eigen::Matrix<Scalar, 3, 1, Options> Vector3
typedef VectorXs ConfigVectorType

Dense vectorized version of a joint configuration vector.

typedef std::map<std::string, ConfigVectorType> ConfigVectorMap

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

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).

Public Functions

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.

PINOCCHIO_ALIGNED_STD_VECTOR (SE3) jointPlacements

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

inline ModelTpl()

Default constructor. Builds an empty model with no joints.

inline ~ModelTpl()
template<typename NewScalar>
inline ModelTpl<NewScalar, Options, JointCollectionTpl> cast() const
Returns:

An expression of *this with the Scalar type casted to NewScalar.

inline bool operator==(const ModelTpl &other) const

Equality comparison operator.

Returns:

true if *this is equal to other.

inline bool operator!=(const ModelTpl &other) const
Returns:

true if *this is NOT equal to other.

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.

Remark

This method also adds a Frame of same name to the vector of frames.

Remark

The inertia supported by the joint is set to Zero.

Remark

Joints need to be added to the tree in a depth-first order.

Template Parameters:

JointModelDerived – The type of the joint model.

Parameters:
  • parent[in] Index of the parent joint.

  • joint_model[in] The joint model.

  • joint_placement[in] Placement of the joint inside its parent joint.

  • joint_name[in] Name of the joint. If empty, the name is random.

Returns:

The index of the new joint.

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.

Remark

This method also adds a Frame of same name to the vector of frames.

Remark

The inertia supported by the joint is set to Zero.

Remark

Joints need to be added to the tree in a depth-first order.

Template Parameters:

JointModelDerived – The type of the joint model.

Parameters:
  • parent[in] Index of the parent joint.

  • joint_model[in] The joint model.

  • joint_placement[in] Placement of the joint inside its parent joint.

  • joint_name[in] Name of the joint. If empty, the name is random.

  • max_effort[in] Maximal joint torque.

  • max_velocity[in] Maximal joint velocity.

  • min_config[in] Lower joint configuration.

  • max_config[in] Upper joint configuration.

Returns:

The index of the new joint.

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.

Remark

This method also adds a Frame of same name to the vector of frames.

Remark

The inertia supported by the joint is set to Zero.

Remark

Joints need to be added to the tree in a depth-first order.

Template Parameters:

JointModelDerived – The type of the joint model.

Parameters:
  • parent[in] Index of the parent joint.

  • joint_model[in] The joint model.

  • joint_placement[in] Placement of the joint inside its parent joint.

  • joint_name[in] Name of the joint. If empty, the name is random.

  • max_effort[in] Maximal joint torque.

  • max_velocity[in] Maximal joint velocity.

  • min_config[in] Lower joint configuration.

  • max_config[in] Upper joint configuration.

  • friction[in] Joint friction parameters.

  • damping[in] Joint damping parameters.

Returns:

The index of the new joint.

FrameIndex addJointFrame(const JointIndex &joint_index, int previous_frame_index = -1)

Add a joint to the frame tree.

Parameters:
  • jointIndex[in] Index of the joint.

  • frameIndex[in] Index of the parent frame. If negative, the parent frame is the frame of the parent joint.

Returns:

The index of the new frame

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.

See also

Model::addJoint

Parameters:
  • joint_index[in] Index of the supporting joint.

  • Y[in] Spatial inertia of the body.

  • body_placement[in] The relative placement of the body regarding to the parent joint. Set default to the Identity placement.

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.

Parameters:
  • body_name[in] Name of the body.

  • parentJoint[in] Index of the parent joint.

  • body_placement[in] The relative placement of the body regarding to the parent joint. Set default to the Identity placement.

  • previousFrame[in] Index of the parent frame. If negative, the parent frame is the frame of the parent joint.

Returns:

The index of the new frame

FrameIndex 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:

name[in] Name of the body.

Returns:

Index of the body.

bool existBodyName(const std::string &name) const

Check if a body given by its name exists.

Parameters:

name[in] Name of the body.

Returns:

True if the body exists in the kinematic tree.

JointIndex 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:

name[in] Name of the joint.

Returns:

Index of the joint.

bool existJointName(const std::string &name) const

Check if a joint given by its name exists.

Parameters:

name[in] Name of the joint.

Returns:

True if the joint exists in the kinematic tree.

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.

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:
  • name[in] Name of the frame.

  • type[in] Type of the frame.

Returns:

Index of the frame.

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.

Parameters:
  • name[in] Name of the frame.

  • type[in] Type of the frame.

Returns:

Returns true if the frame exists.

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).

Parameters:
  • frame[in] The frame to add to the kinematic tree.

  • append_inertia[in] Append 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 D>
inline 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.

The method is a template so that the checkers can be defined in each algorithms.

Parameters:

checker[in] a class, typically defined in the algorithm module, that validates the attributes of model.

Returns:

true if the Model is valid, false otherwise.

std::vector<bool> hasConfigurationLimit()

Check if joints have configuration limits.

Returns:

Returns list of boolean of size model.nq.

std::vector<bool> hasConfigurationLimitInTangent()

Check if joints have configuration limits.

Returns:

Returns list of boolean of size model.nq.

inline bool check() const

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

inline bool check(const Data &data) const

Run checkData on data and current model.

Parameters:

data[in] to be checked wrt *this.

Returns:

true if the data is valid, false otherwise.

Public Members

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar Scalar
int nq

Dimension of the configuration vector representation.

int nv

Dimension of the velocity vector space.

int njoints

Number of joints.

int nbodies

Number of bodies.

int nframes

Number of operational frames.

JointModelVector joints

Model of joint i, encapsulated in a JointModelAccessor.

std::vector<int> idx_qs

Starting index of the joint i in the configuration space.

std::vector<int> nqs

Dimension of the joint i configuration subspace.

std::vector<int> idx_vs

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

std::vector<int> nvs

Dimension of the joint i tangent subspace.

std::vector<JointIndex> parents

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

std::vector<std::string> names

Name of joint i

ConfigVectorMap referenceConfigurations

Map of reference configurations, indexed by user given names.

TangentVectorType rotorInertia

Vector of rotor inertia parameters.

TangentVectorType rotorGearRatio

Vector of rotor gear ratio parameters.

TangentVectorType friction

Vector of joint friction parameters.

TangentVectorType damping

Vector of joint damping parameters.

TangentVectorType effortLimit

Vector of maximal joint torques.

TangentVectorType velocityLimit

Vector of maximal joint velocities.

ConfigVectorType lowerPositionLimit

Lower joint configuration limit.

ConfigVectorType upperPositionLimit

Upper joint configuration limit.

FrameVector frames

Vector of operational frames registered on the model.

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.

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.

Motion gravity

Spatial gravity of the model.

std::string name

Model name;.

Public Static Attributes

static const Vector3 gravity981

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

Protected Functions

void addJointIndexToParentSubtrees(const JointIndex joint_id)

Add the joint_id to its parent subtrees.

Parameters:

joint_id[in] The id of the joint to add to the subtrees