Go to the documentation of this file.
6 #ifndef __pinocchio_multibody_model_hpp__
7 #define __pinocchio_multibody_model_hpp__
32 template<
typename,
int>
class JointCollectionTpl>
38 template<
typename _Scalar,
int _Options,
template<
typename,
int>
class JointCollectionTpl>
44 template<
typename _Scalar,
int _Options,
template<
typename,
int>
class JointCollectionTpl>
47 ,
NumericalBase<ModelTpl<_Scalar, _Options, JointCollectionTpl>>
49 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
80 typedef Eigen::Matrix<Scalar, Eigen::Dynamic, 1, Options>
VectorXs;
81 typedef Eigen::Matrix<Scalar, 3, 1, Options>
Vector3;
220 names[0] =
"universe";
232 template<
typename S2,
int O2>
235 *
this = other.template cast<Scalar>();
239 template<
typename NewScalar>
254 return !(*
this == other);
359 const std::string & body_name,
362 int parentFrame = -1);
421 const std::string &
name,
433 const std::string &
name,
463 return checker.checkModel(*
this);
506 #include "pinocchio/multibody/model.hxx"
508 #if PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
509 #include "pinocchio/multibody/model.txx"
510 #endif // PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
512 #endif // ifndef __pinocchio_multibody_model_hpp__
std::vector< std::string > names
Name of the joints.
FrameVector frames
Vector of operational frames registered on the model.
CRTP class describing the API of the checkers.
bool existJointName(const std::string &name) const
Check if a joint given by its name exists.
SE3Tpl< Scalar, Options > SE3
SE3Vector jointPlacements
Vector of joint placements: placement of a joint i wrt its parent joint frame.
pinocchio::GeomIndex GeomIndex
ConfigVectorType lowerPositionLimit
Lower joint configuration limit.
bool existBodyName(const std::string &name) const
Check if a body given by its name exists.
ModelTpl()
Default constructor. Builds an empty model with no joints.
CastType< NewScalar, ModelTpl >::type cast() const
MotionTpl< Scalar, Options > Motion
bool operator==(const ModelTpl &other) const
Equality comparison operator.
bool operator!=(const ModelTpl &other) const
FrameType
Enum on the possible types of frames.
@ SENSOR
sensor frame: defined in a sensor element
JointModelVector joints
Vector of joint models.
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.
DataTpl< Scalar, Options, JointCollectionTpl > Data
std::string name
Model name.
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.
std::vector< bool > hasConfigurationLimit()
Check if joints have configuration limits.
TangentVectorType rotorInertia
Vector of rotor inertia parameters.
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.
A Plucker coordinate frame attached to a parent joint inside a kinematic tree.
PINOCCHIO_COMPILER_DIAGNOSTIC_POP typedef std::size_t Index
InertiaVector inertias
Vector of spatial inertias supported by each joint.
pinocchio::JointIndex JointIndex
ForceTpl< Scalar, Options > Force
ConfigVectorMap referenceConfigurations
Map of reference configurations, indexed by user given names.
InertiaTpl< Scalar, Options > Inertia
std::vector< IndexVector > subtrees
Vector of joint subtrees. subtree[j] corresponds to the subtree supported by the joint j....
std::vector< int > nqs
Vector of dimension of the joint configuration subspace.
typedef PINOCCHIO_ALIGNED_STD_VECTOR(JointModel) JointModelVector
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.
std::vector< int > nvs
Dimension of the *i*th joint tangent subspace.
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.
std::vector< IndexVector > children
Vector of children index. Chidren of the i*th joint, denoted *mu(i) corresponds to the set (i==parent...
std::vector< int > idx_qs
Vector of starting index of the *i*th joint in the configuration space.
VectorXs TangentVectorType
Dense vectorized version of a joint tangent vector (e.g. velocity, acceleration, etc)....
std::vector< Index > IndexVector
JointDataTpl< Scalar, Options, JointCollectionTpl > JointData
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.
std::vector< bool > hasConfigurationLimitInTangent()
Check if joints have configuration limits.
ModelTpl< NewScalar, Options, JointCollectionTpl > type
pinocchio::FrameIndex FrameIndex
TangentVectorType rotorGearRatio
Vector of rotor gear ratio parameters.
VectorXs armature
Vector of armature values expressed at the joint level This vector may contain the contribution of ro...
Eigen::Matrix< Scalar, Eigen::Dynamic, 1, Options > VectorXs
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar Scalar
void addJointIndexToParentSubtrees(const JointIndex joint_id)
Add the joint_id to its parent subtrees.
int nframes
Number of operational frames.
TangentVectorType velocityLimit
Vector of maximal joint velocities.
int nbodies
Number of bodies.
TangentVectorType friction
Vector of joint friction parameters.
FrameIndex addJointFrame(const JointIndex &joint_index, int previous_frame_index=-1)
Add a joint to the frame tree.
Motion gravity
Spatial gravity of the model.
@ JOINT
joint frame: attached to the child body of a joint (a.k.a. child frame)
static const Vector3 gravity981
Default 3D gravity vector (=(0,0,-9.81)).
JointIndex getJointId(const std::string &name) const
Return the index of a joint given by its name.
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
@ OP_FRAME
operational frame: user-defined frames that are defined at runtime
TangentVectorType damping
Vector of joint damping parameters.
int nv
Dimension of the velocity vector space.
FrameIndex getBodyId(const std::string &name) const
Return the index of a body given by its name.
std::map< std::string, ConfigVectorType > ConfigVectorMap
Map between a string (key) and a configuration vector.
@ FIXED_JOINT
fixed joint frame: joint frame but for a fixed joint
std::vector< IndexVector > supports
Vector of joint supports. supports[j] corresponds to the vector of indices of the joints located on t...
bool check() const
Run check(fusion::list) with DEFAULT_CHECKERS as argument.
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 inert...
TangentVectorType effortLimit
Vector of maximal joint torques.
std::vector< JointIndex > parents
Vector of parent joint indexes. The parent of joint i, denoted li, corresponds to li==parents[i].
Common traits structure to fully define base classes for CRTP.
FrameTpl< Scalar, Options > Frame
VectorXs ConfigVectorType
Dense vectorized version of a joint configuration vector.
std::vector< int > idx_vs
Starting index of the *i*th joint in the tangent configuration space.
Type of the cast of a class C templated by Scalar and Options, to a new NewScalar type....
ModelTpl(const ModelTpl< S2, O2 > &other)
Copy constructor by casting.
ConfigVectorType upperPositionLimit
Upper joint configuration limit.
@ BODY
body frame: attached to the collision, inertial or visual properties of a link
int nq
Dimension of the configuration vector representation.
JointCollectionTpl< Scalar, Options > JointCollection
Main pinocchio namespace.
int njoints
Number of joints.
JointModelTpl< Scalar, Options, JointCollectionTpl > JointModel
pinocchio
Author(s):
autogenerated on Sun Nov 10 2024 03:43:00