5 #ifdef PINOCCHIO_WITH_URDFDOM
12 #include <boost/python.hpp>
21 #ifdef PINOCCHIO_WITH_URDFDOM
23 Model buildModelFromUrdf(
const bp::object & filename,
const bool mimic)
30 Model & buildModelFromUrdf(
const bp::object & filename,
Model &
model,
const bool mimic)
36 buildModelFromUrdf(
const bp::object & filename,
const JointModel & root_joint,
const bool mimic)
43 Model buildModelFromUrdf(
44 const bp::object & filename,
46 const std::string & root_joint_name,
54 Model & buildModelFromUrdf(
60 Model & buildModelFromUrdf(
61 const bp::object & filename,
63 const std::string & root_joint_name,
68 path(filename), root_joint, root_joint_name,
model,
false, mimic);
72 const std::string & xml_stream,
const JointModel & root_joint,
const bool mimic)
80 const std::string & xml_stream,
82 const std::string & root_joint_name,
87 xml_stream, root_joint, root_joint_name,
model,
false, mimic);
92 const std::string & xml_stream,
102 const std::string & xml_stream,
104 const std::string & root_joint_name,
109 xml_stream, root_joint, root_joint_name,
model,
false, mimic);
131 #ifdef PINOCCHIO_WITH_URDFDOM
134 "buildModelFromUrdf",
135 static_cast<Model (*)(
const bp::object &,
const JointModel &,
const bool)
>(
136 pinocchio::python::buildModelFromUrdf),
137 (bp::arg(
"urdf_filename"), bp::arg(
"root_joint"), bp::arg(
"mimic") =
false),
138 "Parse the URDF file given in input and return a pinocchio Model starting with the "
139 "given root joint.");
142 "buildModelFromUrdf",
143 static_cast<Model (*)(
144 const bp::object &,
const JointModel &,
const std::string &,
const bool)
>(
145 pinocchio::python::buildModelFromUrdf),
146 (bp::arg(
"urdf_filename"), bp::arg(
"root_joint"), bp::arg(
"root_joint_name"),
147 bp::arg(
"mimic") =
false),
148 "Parse the URDF file given in input and return a pinocchio Model starting with the "
149 "given root joint with its specified name.");
152 "buildModelFromUrdf",
153 static_cast<Model (*)(
const bp::object &,
const bool)
>(
154 pinocchio::python::buildModelFromUrdf),
155 (bp::arg(
"urdf_filename"), bp::arg(
"mimic") =
false),
156 "Parse the URDF file given in input and return a pinocchio Model.");
159 "buildModelFromUrdf",
160 static_cast<Model & (*)(
const bp::object &,
Model &,
const bool)
>(
161 pinocchio::python::buildModelFromUrdf),
162 (bp::arg(
"urdf_filename"), bp::arg(
"model"), bp::arg(
"mimic") =
false),
163 "Append to a given model a URDF structure given by its filename.",
164 bp::return_internal_reference<2>());
167 "buildModelFromUrdf",
169 pinocchio::python::buildModelFromUrdf),
170 (bp::arg(
"urdf_filename"), bp::arg(
"root_joint"), bp::arg(
"model"),
171 bp::arg(
"mimic") =
false),
172 "Append to a given model a URDF structure given by its filename and the root joint.\n"
173 "Remark: In the URDF format, a joint of type fixed can be defined. For efficiency reasons,"
174 "it is treated as operational frame and not as a joint of the model.",
175 bp::return_internal_reference<3>());
178 "buildModelFromUrdf",
179 static_cast<Model & (*)(
const bp::object &,
const JointModel &,
const std::string &,
180 Model &,
const bool)
>(pinocchio::python::buildModelFromUrdf),
181 (bp::arg(
"urdf_filename"), bp::arg(
"root_joint"), bp::arg(
"root_joint_name"),
182 bp::arg(
"model"), bp::arg(
"mimic") =
false),
183 "Append to a given model a URDF structure given by its filename and the root joint with "
184 "its specified name.\n"
185 "Remark: In the URDF format, a joint of type fixed can be defined. For efficiency reasons,"
186 "it is treated as operational frame and not as a joint of the model.",
187 bp::return_internal_reference<3>());
191 static_cast<Model (*)(
const std::string &,
const JointModel &,
const bool)
>(
193 (bp::arg(
"urdf_xml_stream"), bp::arg(
"root_joint"), bp::arg(
"mimic") =
false),
194 "Parse the URDF XML stream given in input and return a pinocchio Model starting with "
195 "the given root joint.");
199 static_cast<Model (*)(
200 const std::string &,
const JointModel &,
const std::string &,
const bool)
>(
202 (bp::arg(
"urdf_xml_stream"), bp::arg(
"root_joint"), bp::arg(
"root_joint_name"),
203 bp::arg(
"mimic") =
false),
204 "Parse the URDF XML stream given in input and return a pinocchio Model starting with "
205 "the given root joint with its specified name.");
211 (bp::arg(
"urdf_xml_stream"), bp::arg(
"root_joint"), bp::arg(
"model"),
212 bp::arg(
"mimic") =
false),
213 "Parse the URDF XML stream given in input and append it to the input model with the "
214 "given interfacing joint.",
215 bp::return_internal_reference<3>());
219 static_cast<Model & (*)(
const std::string &,
const JointModel &,
const std::string &,
221 (bp::arg(
"urdf_xml_stream"), bp::arg(
"root_joint"), bp::arg(
"root_joint_name"),
222 bp::arg(
"model"), bp::arg(
"mimic") =
false),
223 "Parse the URDF XML stream given in input and append it to the input model with the "
224 "given interfacing joint with its specified name.",
225 bp::return_internal_reference<3>());
229 static_cast<Model (*)(
const std::string &,
const bool)
>(
231 (bp::arg(
"urdf_xml_stream"), bp::arg(
"mimic") =
false),
232 "Parse the URDF XML stream given in input and return a pinocchio Model.");
236 static_cast<Model & (*)(
const std::string &,
Model &,
const bool)
>(
238 (bp::arg(
"urdf_xml_stream"), bp::arg(
"model"), bp::arg(
"mimic") =
false),
239 "Parse the URDF XML stream given in input and append it to the input model.",
240 bp::return_internal_reference<2>());