@@ -31,6 +31,13 @@ namespace pinocchio
3131 return pinocchio::urdf::buildModel (filename, model);
3232 }
3333
34+ Model buildModelFromUrdf (const std::string & filename, const JointModel & root_joint)
35+ {
36+ Model model;
37+ pinocchio::urdf::buildModel (filename, root_joint, " root_joint" , model);
38+ return model;
39+ }
40+
3441 Model buildModelFromUrdf (
3542 const std::string & filename,
3643 const JointModel & root_joint,
@@ -41,6 +48,12 @@ namespace pinocchio
4148 return model;
4249 }
4350
51+ Model &
52+ buildModelFromUrdf (const std::string & filename, const JointModel & root_joint, Model & model)
53+ {
54+ return pinocchio::urdf::buildModel (filename, root_joint, " root_joint" , model);
55+ }
56+
4457 Model & buildModelFromUrdf (
4558 const std::string & filename,
4659 const JointModel & root_joint,
@@ -50,6 +63,13 @@ namespace pinocchio
5063 return pinocchio::urdf::buildModel (filename, root_joint, rootJointName, model);
5164 }
5265
66+ Model buildModelFromXML (const std::string & XMLstream, const JointModel & root_joint)
67+ {
68+ Model model;
69+ pinocchio::urdf::buildModelFromXML (XMLstream, root_joint, " root_joint" , model);
70+ return model;
71+ }
72+
5373 Model buildModelFromXML (
5474 const std::string & XMLstream,
5575 const JointModel & root_joint,
@@ -60,6 +80,13 @@ namespace pinocchio
6080 return model;
6181 }
6282
83+ Model &
84+ buildModelFromXML (const std::string & XMLstream, const JointModel & root_joint, Model & model)
85+ {
86+ pinocchio::urdf::buildModelFromXML (XMLstream, root_joint, " root_joint" , model);
87+ return model;
88+ }
89+
6390 Model & buildModelFromXML (
6491 const std::string & XMLstream,
6592 const JointModel & root_joint,
@@ -90,6 +117,14 @@ namespace pinocchio
90117
91118#ifdef PINOCCHIO_WITH_URDFDOM
92119
120+ bp::def (
121+ " buildModelFromUrdf" ,
122+ static_cast <Model (*)(const std::string &, const JointModel &)>(
123+ pinocchio::python::buildModelFromUrdf),
124+ bp::args (" urdf_filename" , " root_joint" ),
125+ " Parse the URDF file given in input and return a pinocchio Model starting with the "
126+ " given root joint." );
127+
93128 bp::def (
94129 " buildModelFromUrdf" ,
95130 static_cast <Model (*)(const std::string &, const JointModel &, const std::string &)>(
@@ -112,6 +147,16 @@ namespace pinocchio
112147 " Append to a given model a URDF structure given by its filename." ,
113148 bp::return_internal_reference<2 >());
114149
150+ bp::def (
151+ " buildModelFromUrdf" ,
152+ static_cast <Model & (*)(const std::string &, const JointModel &, Model &)>(
153+ pinocchio::python::buildModelFromUrdf),
154+ bp::args (" urdf_filename" , " root_joint" , " model" ),
155+ " Append to a given model a URDF structure given by its filename and the root joint.\n "
156+ " Remark: In the URDF format, a joint of type fixed can be defined. For efficiency reasons,"
157+ " it is treated as operational frame and not as a joint of the model." ,
158+ bp::return_internal_reference<3 >());
159+
115160 bp::def (
116161 " buildModelFromUrdf" ,
117162 static_cast <Model & (*)(const std::string &, const JointModel &, const std::string &,
@@ -122,6 +167,14 @@ namespace pinocchio
122167 " it is treated as operational frame and not as a joint of the model." ,
123168 bp::return_internal_reference<3 >());
124169
170+ bp::def (
171+ " buildModelFromXML" ,
172+ static_cast <Model (*)(const std::string &, const JointModel &)>(
173+ pinocchio::python::buildModelFromXML),
174+ bp::args (" urdf_xml_stream" , " root_joint" ),
175+ " Parse the URDF XML stream given in input and return a pinocchio Model starting with "
176+ " the given root joint." );
177+
125178 bp::def (
126179 " buildModelFromXML" ,
127180 static_cast <Model (*)(const std::string &, const JointModel &, const std::string &)>(
@@ -130,6 +183,15 @@ namespace pinocchio
130183 " Parse the URDF XML stream given in input and return a pinocchio Model starting with "
131184 " the given root joint." );
132185
186+ bp::def (
187+ " buildModelFromXML" ,
188+ static_cast <Model & (*)(const std::string &, const JointModel &, Model &)>(
189+ pinocchio::python::buildModelFromXML),
190+ bp::args (" urdf_xml_stream" , " root_joint" , " model" ),
191+ " Parse the URDF XML stream given in input and append it to the input model with the "
192+ " given interfacing joint." ,
193+ bp::return_internal_reference<3 >());
194+
133195 bp::def (
134196 " buildModelFromXML" ,
135197 static_cast <Model & (*)(const std::string &, const JointModel &, const std::string &,
0 commit comments