6 #ifndef __pinocchio_python_multibody_model_hpp__ 7 #define __pinocchio_python_multibody_model_hpp__ 11 #include "pinocchio/multibody/model.hpp" 12 #include "pinocchio/serialization/model.hpp" 14 #include <boost/python/overloads.hpp> 18 #include "pinocchio/algorithm/check.hpp" 34 BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(getFrameId_overload,Model::getFrameId,1,2)
35 BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(existFrame_overload,
Model::existFrame,1,2)
36 BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(addJointFrame_overload,
Model::addJointFrame,1,2)
38 template<typename
Model>
43 return bp::make_tuple();
49 return bp::make_tuple(bp::str(str));
54 if(bp::len(tup) == 0 || bp::len(tup) > 1)
56 throw eigenpy::Exception(
"Pickle was not able to reconstruct the model from the loaded data.\n" 57 "The pickle data structure contains too many elements.");
60 bp::object py_obj = tup[0];
61 boost::python::extract<std::string> obj_as_string(py_obj.ptr());
62 if(obj_as_string.check())
64 const std::string str = obj_as_string;
69 throw eigenpy::Exception(
"Pickle was not able to reconstruct the model from the loaded data.\n" 70 "The entry is not a string.");
76 template<
typename Model>
78 :
public bp::def_visitor< ModelPythonVisitor<Model> >
98 BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(addFrame_overload,Model::addFrame,1,2)
103 template<class PyClass>
104 void visit(PyClass& cl)
const 107 .def(bp::init<>(bp::arg(
"self"),
108 "Default constructor. Constructs an empty model."))
113 .add_property(
"njoints", &Model::njoints)
114 .add_property(
"nbodies", &Model::nbodies)
115 .add_property(
"nframes", &Model::nframes)
116 .add_property(
"inertias",&Model::inertias)
117 .add_property(
"jointPlacements",&Model::jointPlacements)
118 .add_property(
"joints",&Model::joints)
119 .add_property(
"idx_qs",&Model::idx_qs)
120 .add_property(
"nqs",&Model::nqs)
121 .add_property(
"idx_vs",&Model::idx_vs)
122 .add_property(
"nvs",&Model::nvs)
123 .add_property(
"parents",&Model::parents)
124 .add_property(
"names",&Model::names)
126 .def_readwrite(
"referenceConfigurations", &Model::referenceConfigurations)
128 .def_readwrite(
"rotorInertia",&Model::rotorInertia,
129 "Vector of rotor inertia parameters.")
130 .def_readwrite(
"rotorGearRatio",&Model::rotorGearRatio,
131 "Vector of rotor gear ratio parameters.")
132 .def_readwrite(
"friction",&Model::friction,
133 "Vector of joint friction parameters.")
134 .def_readwrite(
"damping",&Model::damping,
135 "Vector of joint damping parameters.")
136 .def_readwrite(
"effortLimit",&Model::effortLimit,
138 .def_readwrite(
"velocityLimit",&Model::velocityLimit,
139 "Joint max velocity.")
141 "Limit for joint lower position.")
143 "Limit for joint upper position.")
145 .def_readwrite(
"frames",&Model::frames,
146 "Vector of frames contained in the model.")
148 .def_readwrite(
"supports",
150 "Vector of supports. supports[j] corresponds to the list of joints on the path between\n" 151 "the current *j* to the root of the kinematic tree.")
153 .def_readwrite(
"subtrees",
155 "Vector of subtrees. subtree[j] corresponds to the subtree supported by the joint j.")
158 "Motion vector corresponding to the gravity field expressed in the world Frame.")
161 .def(
"addJoint",&ModelPythonVisitor::addJoint0,
162 bp::args(
"self",
"parent_id",
"joint_model",
"joint_placement",
"joint_name"),
163 "Adds a joint to the kinematic tree. The joint is defined by its placement relative to its parent joint and its name.")
164 .def(
"addJoint",&ModelPythonVisitor::addJoint1,
165 bp::args(
"self",
"parent_id",
"joint_model",
"joint_placement",
"joint_name",
166 "max_effort",
"max_velocity",
"min_config",
"max_config"),
167 "Adds a joint to the kinematic tree with given bounds. The joint is defined by its placement relative to its parent joint and its name." 168 "This signature also takes as input effort, velocity limits as well as the bounds on the joint configuration.")
169 .def(
"addJoint",&ModelPythonVisitor::addJoint2,
170 bp::args(
"self",
"parent_id",
"joint_model",
"joint_placement",
"joint_name",
171 "max_effort",
"max_velocity",
"min_config",
"max_config",
172 "friction",
"damping"),
173 "Adds a joint to the kinematic tree with given bounds. The joint is defined by its placement relative to its parent joint and its name.\n" 174 "This signature also takes as input effort, velocity limits as well as the bounds on the joint configuration.\n" 175 "The user should also provide the friction and damping related to the joint.")
176 .def(
"addJointFrame", &Model::addJointFrame,
177 addJointFrame_overload(
bp::args(
"self",
"joint_id",
"frame_id"),
178 "Add the joint provided by its joint_id as a frame to the frame tree.\n" 179 "The frame_id may be optionally provided."))
180 .def(
"appendBodyToJoint",&Model::appendBodyToJoint,
181 bp::args(
"self",
"joint_id",
"body_inertia",
"body_placement"),
182 "Appends a body to the joint given by its index. The body is defined by its inertia, its relative placement regarding to the joint and its name.")
184 .def(
"addBodyFrame", &Model::addBodyFrame,
bp::args(
"self",
"body_name",
"parentJoint",
"body_placement",
"previous_frame(parent frame)"),
"add a body to the frame tree")
185 .def(
"getBodyId",&Model::getBodyId,
bp::args(
"self",
"name"),
"Return the index of a frame of type BODY given by its name")
186 .def(
"existBodyName", &Model::existBodyName,
bp::args(
"self",
"name"),
"Check if a frame of type BODY exists, given its name")
187 .def(
"getJointId",&Model::getJointId,
bp::args(
"self",
"name"),
"Return the index of a joint given by its name")
188 .def(
"existJointName", &Model::existJointName,
bp::args(
"self",
"name"),
"Check if a joint given by its name exists")
190 .def(
"getFrameId",&Model::getFrameId,getFrameId_overload(
bp::args(
"self",
"name",
"type"),
"Returns the index of the frame given by its name and its type. If the frame is not in the frames vector, it returns the current size of the frames vector."))
192 .def(
"existFrame",&Model::existFrame,existFrame_overload(
bp::args(
"self",
"name",
"type"),
"Returns true if the frame given by its name exists inside the Model with the given type."))
194 .def(
"addFrame",&Model::addFrame,
195 addFrame_overload((bp::arg(
"self"), bp::arg(
"frame"), bp::arg(
"append_inertia") =
true),
196 "Add a frame to the vector of frames. If append_inertia set to True, " 197 "the inertia value contained in frame will be added to the inertia supported by the parent joint."))
201 "Create a Data object for the given model.")
203 .def(
"check",(
bool (
Model::*)(
const Data &)
const) &Model::check,
bp::args(
"self",
"data"),
204 "Check consistency of data wrt model.")
206 .def(bp::self == bp::self)
207 .def(bp::self != bp::self)
217 return model.
addJoint(parent_id,jmodel,joint_placement,joint_name);
225 const VectorXs & max_effort,
226 const VectorXs & max_velocity,
227 const VectorXs & min_config,
228 const VectorXs & max_config)
230 return model.
addJoint(parent_id,jmodel,joint_placement,joint_name,
231 max_effort,max_velocity,min_config,max_config);
239 const VectorXs & max_effort,
240 const VectorXs & max_velocity,
241 const VectorXs & min_config,
242 const VectorXs & max_config,
243 const VectorXs & friction,
244 const VectorXs & damping)
246 return model.
addJoint(parent_id,jmodel,joint_placement,joint_name,
247 max_effort,max_velocity,min_config,max_config,
264 static Index
index(std::vector<T>
const&
x,
268 for(
typename std::vector<T>::const_iterator it = x.begin(); it != x.end(); ++it, ++
i)
282 typedef bp::map_indexing_suite<ConfigVectorMap,false> map_indexing_suite;
284 serialize< std::vector<Index> >();
286 serialize< std::vector<IndexVector> >();
288 serialize< std::vector<std::string> >();
290 serialize< std::vector<bool> >();
292 serialize< std::vector<Scalar> >();
293 bp::class_<typename Model::ConfigVectorMap>(
"StdMap_String_VectorXd")
294 .def(map_indexing_suite())
298 bp::class_<Model>(
"Model",
299 "Articulated Rigid Body model",
312 #endif // ifndef __pinocchio_python_multibody_model_hpp__
int nv(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointNvVisitor to get the dimension of the joint tangent space...
static void setstate(Model &model, bp::tuple tup)
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)
std::string saveToString() const
Saves a Derived object to a string.
int nq(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointNqVisitor to get the dimension of the joint configuration space...
Model::JointIndex JointIndex
A Plucker coordinate frame attached to a parent joint inside a kinematic tree.
JointDataTpl< Scalar, Options, JointCollectionTpl > createData(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through CreateData visitor to create a JointDataTpl.
Expose an std::vector from a type given as template argument.
static bp::tuple getstate(const Model &model)
Set the Python method str and repr to use the overloading operator<<.
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)
Model::FrameIndex FrameIndex
pinocchio::FrameIndex FrameIndex
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.
static Data createData(const Model &model)
std::vector< Index > IndexVector
pinocchio::JointIndex JointIndex
std::map< std::string, ConfigVectorType > ConfigVectorMap
Map between a string (key) and a configuration vector.
Add the Python method copy to allow a copy of this by calling the copy constructor.
static bp::tuple getinitargs(const Model &)
Model::IndexVector IndexVector
Main pinocchio namespace.
Eigen::Matrix< Scalar, Eigen::Dynamic, 1, Options > VectorXs
void loadFromString(const std::string &str)
Loads a Derived object from a string.
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.
#define EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(...)
static JointIndex addJoint0(Model &model, JointIndex parent_id, const JointModel &jmodel, const SE3 &joint_placement, const std::string &joint_name)
Create a pickle interface for the std::map and aligned map.