|
enum | { Options = _Options
} |
|
typedef std::map< std::string, ConfigVectorType > | ConfigVectorMap |
|
typedef VectorXs | ConfigVectorType |
| Dense vectorized version of a joint configuration vector.
|
|
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 _Scalar | Scalar |
|
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).
|
|
typedef Eigen::Matrix< Scalar, 3, 1, Options > | Vector3 |
|
typedef Eigen::Matrix< Scalar, Eigen::Dynamic, 1, Options > | VectorXs |
|
|
| ModelTpl () |
| Default constructor. Builds an empty model with no joints.
|
|
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) |
| Adds a frame to the kinematic tree. 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 given bounds. 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...
|
|
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.
|
|
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...
|
|
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.
|
|
| PINOCCHIO_ALIGNED_STD_VECTOR (SE3) jointPlacements |
| Placement (SE3) of the input of joint i regarding to the parent joint output li.
|
|
void | loadFromBinary (const std::string &filename) |
| Loads a Derived object from an binary file.
|
|
void | loadFromString (const std::string &str) |
| Loads a Derived object from a string.
|
|
void | loadFromStringStream (std::istringstream &is) |
| Loads a Derived object from a stream string.
|
|
void | loadFromText (const std::string &filename) |
| Loads a Derived object from a text file.
|
|
void | loadFromXML (const std::string &filename, const std::string &tag_name) |
| Loads a Derived object from an XML file.
|
|
void | saveToBinary (const std::string &filename) const |
| Saves a Derived object as an binary file.
|
|
std::string | saveToString () const |
| Saves a Derived object to a string.
|
|
void | saveToStringStream (std::stringstream &ss) const |
| Saves a Derived object to a string stream.
|
|
void | saveToText (const std::string &filename) const |
| Saves a Derived object as a text file.
|
|
void | saveToXML (const std::string &filename, const std::string &tag_name) const |
| Saves a Derived object as an XML file.
|
|
|
TangentVectorType | effortLimit |
| Vector of maximal joint torques.
|
|
FrameVector | frames |
| Vector of operational frames registered on the model.
|
|
Motion | gravity |
| Spatial gravity of the model.
|
|
std::vector< int > | idx_qs |
| Starting index of the joint i in the configuration space.
|
|
std::vector< int > | idx_vs |
| Starting index of the joint i in the tangent configuration space.
|
|
JointModelVector | joints |
| Model of joint i, encapsulated in a JointModelAccessor.
|
|
VectorXs | lowerPositionLimit |
| Lower joint configuration limit.
|
|
std::string | name |
| Model name;.
|
|
std::vector< std::string > | names |
| Name of joint i
|
|
int | nbodies |
| Number of bodies.
|
|
int | nframes |
| Number of operational frames.
|
|
int | njoints |
| Number of joints.
|
|
int | nq |
| Dimension of the configuration vector representation.
|
|
std::vector< int > | nqs |
| Dimension of the joint i configuration subspace.
|
|
int | nv |
| Dimension of the velocity vector 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]).
|
|
ConfigVectorMap | referenceConfigurations |
| Map of reference configurations, indexed by user given names.
|
|
VectorXs | rotorGearRatio |
| Vector of rotor gear ratio parameters.
|
|
VectorXs | rotorInertia |
| Vector of rotor inertia parameters.
|
|
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.
|
|
std::vector< IndexVector > | 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.
|
|
VectorXs | upperPositionLimit |
| Upper joint configuration limit.
|
|
TangentVectorType | velocityLimit |
| Vector of maximal joint velocities.
|
|
template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
struct pinocchio::ModelTpl< _Scalar, _Options, JointCollectionTpl >
Definition at line 23 of file fwd.hpp.