Go to the documentation of this file.
6 #ifndef __pinocchio_python_multibody_model_hpp__
7 #define __pinocchio_python_multibody_model_hpp__
14 #include <boost/python/overloads.hpp>
30 #if EIGENPY_VERSION_AT_MOST(2, 8, 1)
40 template<
typename Model>
65 template<
class PyClass>
68 cl.def(bp::init<>(bp::arg(
"self"),
"Default constructor. Constructs an empty model."))
69 .def(bp::init<const Model &>((bp::arg(
"self"), bp::arg(
"clone")),
"Copy constructor"))
72 .add_property(
"nq", &
Model::nq,
"Dimension of the configuration vector representation.")
73 .add_property(
"nv", &
Model::nv,
"Dimension of the velocity vector space.")
78 "inertias", &
Model::inertias,
"Vector of spatial inertias supported by each joint.")
81 "Vector of joint placements: placement of a joint *i* wrt its parent joint frame.")
82 .add_property(
"joints", &
Model::joints,
"Vector of joint models.")
85 "Vector of starting index of the *i*th joint in the configuration space.")
87 "nqs", &
Model::nqs,
"Vector of dimension of the joint configuration subspace.")
90 "Starting index of the *i*th joint in the tangent configuration space.")
91 .add_property(
"nvs", &
Model::nvs,
"Dimension of the *i*th joint tangent subspace.")
94 "Vector of parent joint indexes. The parent of joint *i*, denoted *li*, "
95 "corresponds to li==parents[i].")
98 "Vector of children index. Chidren of the *i*th joint, denoted *mu(i)* "
99 "corresponds to the set (i==parents[k] for k in mu(i)).")
100 .add_property(
"names", &
Model::names,
"Name of the joints.")
101 .def_readwrite(
"name", &
Model::name,
"Name of the model.")
104 "Map of reference configurations, indexed by user given names.")
111 .def_readwrite(
"friction", &
Model::friction,
"Vector of joint friction parameters.")
112 .def_readwrite(
"damping", &
Model::damping,
"Vector of joint damping parameters.")
120 .def_readwrite(
"frames", &
Model::frames,
"Vector of frames contained in the model.")
124 "Vector of supports. supports[j] corresponds to the list of joints on the "
126 "the current *j* to the root of the kinematic tree.")
130 "Vector of subtrees. subtree[j] corresponds to the subtree supported by the joint j.")
134 "Motion vector corresponding to the gravity field expressed in the world Frame.")
139 bp::args(
"self",
"parent_id",
"joint_model",
"joint_placement",
"joint_name"),
140 "Adds a joint to the kinematic tree. The joint is defined by its placement relative "
141 "to its parent joint and its name.")
145 "self",
"parent_id",
"joint_model",
"joint_placement",
"joint_name",
"max_effort",
146 "max_velocity",
"min_config",
"max_config"),
147 "Adds a joint to the kinematic tree with given bounds. The joint is defined by its "
148 "placement relative to its parent joint and its name."
149 "This signature also takes as input effort, velocity limits as well as the bounds "
150 "on the joint configuration.")
154 "self",
"parent_id",
"joint_model",
"joint_placement",
"joint_name",
"max_effort",
155 "max_velocity",
"min_config",
"max_config",
"friction",
"damping"),
156 "Adds a joint to the kinematic tree with given bounds. The joint is defined by its "
157 "placement relative to its parent joint and its name.\n"
158 "This signature also takes as input effort, velocity limits as well as the bounds "
159 "on the joint configuration.\n"
160 "The user should also provide the friction and damping related to the joint.")
163 (bp::arg(
"self"), bp::arg(
"joint_id"), bp::arg(
"frame_id") = 0),
164 "Add the joint provided by its joint_id as a frame to the frame tree.\n"
165 "The frame_id may be optionally provided.")
168 bp::args(
"self",
"joint_id",
"body_inertia",
"body_placement"),
169 "Appends a body to the joint given by its index. The body is defined by its "
170 "inertia, its relative placement regarding to the joint and its name.")
174 bp::args(
"self",
"body_name",
"parentJoint",
"body_placement",
"previous_frame"),
175 "add a body to the frame tree")
178 "Return the index of a frame of type BODY given by its name")
181 "Check if a frame of type BODY exists, given its name")
184 "Return the index of a joint given by its name")
187 "Check if a joint given by its name exists")
191 (bp::arg(
"self"), bp::arg(
"name"),
193 "Returns the index of the frame given by its name and its type."
194 "If the frame is not in the frames vector, it returns the current size of the "
199 (bp::arg(
"self"), bp::arg(
"name"),
201 "Returns true if the frame given by its name exists inside the Model with the given "
206 (bp::arg(
"self"), bp::arg(
"frame"), bp::arg(
"append_inertia") =
true),
207 "Add a frame to the vector of frames. If append_inertia set to True, "
208 "the inertia value contained in frame will be added to the inertia supported by the "
213 "Create a Data object for the given model.")
217 "Check consistency of data wrt model.")
221 "Returns list of boolean if joints have configuration limit.")
225 "Returns list of boolean if joints have configuration limit in tangent space .")
227 #ifndef PINOCCHIO_PYTHON_SKIP_COMPARISON_OPERATIONS
229 .def(bp::self == bp::self)
230 .def(bp::self != bp::self)
233 .PINOCCHIO_ADD_STATIC_PROPERTY_READONLY_BYVALUE(
234 Model, gravity981,
"Default gravity field value on the Earth.");
258 return model.addJoint(
276 return model.addJoint(
278 max_config, friction, damping);
300 for (
typename std::vector<T>::const_iterator
it =
x.begin();
it !=
x.end(); ++
it, ++
i)
314 typedef bp::map_indexing_suite<ConfigVectorMap, false> map_indexing_suite;
316 serialize<std::vector<Index>>();
318 serialize<std::vector<IndexVector>>();
323 #if defined(PINOCCHIO_PYTHON_INTERFACE_MAIN_MODULE)
324 bp::scope().attr(
"StdVec_Double") = bp::scope().attr(
"StdVec_Scalar");
327 serialize<std::vector<std::string>>();
328 serialize<std::vector<bool>>();
329 #ifndef PINOCCHIO_PYTHON_NO_SERIALIZATION
330 serialize<std::vector<Scalar>>();
332 bp::class_<typename Model::ConfigVectorMap>(
"StdMap_String_VectorXd")
333 .def(map_indexing_suite())
337 bp::class_<Model>(
"Model",
"Articulated Rigid Body model", bp::no_init)
344 #ifndef PINOCCHIO_PYTHON_NO_SERIALIZATION
354 #endif // ifndef __pinocchio_python_multibody_model_hpp__
std::vector< std::string > names
Name of the joints.
static JointIndex addJoint1(Model &model, JointIndex parent_id, const JointModel &jmodel, 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)
FrameVector frames
Vector of operational frames registered on the model.
bool existJointName(const std::string &name) const
Check if a joint given by its name exists.
SE3Vector jointPlacements
Vector of joint placements: placement of a joint i wrt its parent joint frame.
ConfigVectorType lowerPositionLimit
Lower joint configuration limit.
bool existBodyName(const std::string &name) const
Check if a body given by its name exists.
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.
std::string name
Model name.
static Data createData(const Model &model)
std::vector< bool > hasConfigurationLimit()
Check if joints have configuration limits.
TangentVectorType rotorInertia
Vector of rotor inertia parameters.
A Plucker coordinate frame attached to a parent joint inside a kinematic tree.
InertiaVector inertias
Vector of spatial inertias supported by each joint.
pinocchio::JointIndex JointIndex
ConfigVectorMap referenceConfigurations
Map of reference configurations, indexed by user given names.
std::vector< IndexVector > subtrees
Vector of joint subtrees. subtree[j] corresponds to the subtree supported by the joint j....
#define EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(...)
std::vector< int > nqs
Vector of dimension of the joint configuration subspace.
Set the Python method str and repr to use the overloading operator<<.
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.
Model::JointModel JointModel
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.
std::vector< Index > IndexVector
void visit(PyClass &cl) const
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.
static JointIndex addJoint0(Model &model, JointIndex parent_id, const JointModel &jmodel, const SE3 &joint_placement, const std::string &joint_name)
pinocchio::FrameIndex FrameIndex
JointModel::JointModelVariant JointModelVariant
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...
Add the Python method copy to allow a copy of this by calling the copy constructor.
Eigen::Matrix< Scalar, Eigen::Dynamic, 1, Options > VectorXs
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar Scalar
Model::IndexVector IndexVector
Model::FrameIndex FrameIndex
int nframes
Number of operational frames.
static Index index(std::vector< T > const &x, typename std::vector< T >::value_type const &v)
Provide equivalent to python list index function for vectors.
TangentVectorType velocityLimit
Vector of maximal joint velocities.
int nbodies
Number of bodies.
TangentVectorType friction
Vector of joint friction parameters.
Add the Python method cast.
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)
JointIndex getJointId(const std::string &name) const
Return the index of a joint given by its name.
@ 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.
JointCollection::JointModelVariant JointModelVariant
static JointIndex addJoint2(Model &model, JointIndex parent_id, const JointModel &jmodel, 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)
@ 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].
std::vector< int > idx_vs
Starting index of the *i*th joint in the tangent configuration space.
Model::JointIndex JointIndex
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.
Create a pickle interface for the std::map and aligned map.
JointCollectionTpl & model
Main pinocchio namespace.
int njoints
Number of joints.
pinocchio
Author(s):
autogenerated on Fri Nov 1 2024 02:41:47