GCC Code Coverage Report


Directory: ./
File: include/pinocchio/parsers/urdf.hpp
Date: 2025-04-30 16:14:33
Exec Total Coverage
Lines: 4 4 100.0%
Branches: 2 4 50.0%

Line Branch Exec Source
1 //
2 // Copyright (c) 2015-2021 CNRS INRIA
3 // Copyright (c) 2015 Wandercraft, 86 rue de Paris 91400 Orsay, France.
4 //
5
6 #ifndef __pinocchio_parsers_urdf_hpp__
7 #define __pinocchio_parsers_urdf_hpp__
8
9 #include "pinocchio/multibody/model.hpp"
10 #include "pinocchio/multibody/geometry.hpp"
11 #include "pinocchio/parsers/meshloader-fwd.hpp"
12
13 #include <memory>
14
15 /// \cond
16 // forward declaration of the unique type from urdfdom which is expose.
17 namespace urdf
18 {
19 class ModelInterface;
20 }
21 /// \endcond
22
23 namespace pinocchio
24 {
25 namespace urdf
26 {
27
28 ///
29 /// \brief Build the model from a URDF file with a particular joint as root of the model tree
30 /// inside the model given as reference argument.
31 ///
32 /// \param[in] filename The URDF complete file path.
33 /// \param[in] rootJoint The joint at the root of the model tree.
34 /// \param[in] rootJointName Name of the rootJoint.
35 /// \param[in] verbose Print parsing info.
36 /// \param[in] mimic Parsing joints as mimic or not.
37 /// \param[out] model Reference model where to put the parsed information.
38 /// \return Return the reference on argument model for convenience.
39 ///
40 template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
41 ModelTpl<Scalar, Options, JointCollectionTpl> & buildModel(
42 const std::string & filename,
43 const typename ModelTpl<Scalar, Options, JointCollectionTpl>::JointModel & rootJoint,
44 const std::string & rootJointName,
45 ModelTpl<Scalar, Options, JointCollectionTpl> & model,
46 const bool verbose = false,
47 const bool mimic = false);
48
49 ///
50 /// \brief Build the model from a URDF file with a particular joint as root of the model tree
51 /// inside the model given as reference argument.
52 ///
53 /// \param[in] filename The URDF complete file path.
54 /// \param[in] rootJoint The joint at the root of the model tree.
55 /// \param[in] mimic Parsing joints as mimic or not.
56 /// \param[in] verbose Print parsing info.
57 /// \param[out] model Reference model where to put the parsed information.
58 /// \return Return the reference on argument model for convenience.
59 ///
60 template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
61 ModelTpl<Scalar, Options, JointCollectionTpl> & buildModel(
62 const std::string & filename,
63 const typename ModelTpl<Scalar, Options, JointCollectionTpl>::JointModel & rootJoint,
64 ModelTpl<Scalar, Options, JointCollectionTpl> & model,
65 const bool verbose = false,
66 const bool mimic = false);
67
68 ///
69 /// \brief Build the model from a URDF file with a fixed joint as root of the model tree.
70 ///
71 /// \param[in] filename The URDF complete file path.
72 /// \param[in] mimic Parsing joints as mimic or not.
73 /// \param[in] verbose Print parsing info.
74 /// \param[out] model Reference model where to put the parsed information.
75 /// \return Return the reference on argument model for convenience.
76 ///
77 template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
78 ModelTpl<Scalar, Options, JointCollectionTpl> & buildModel(
79 const std::string & filename,
80 ModelTpl<Scalar, Options, JointCollectionTpl> & model,
81 const bool verbose = false,
82 const bool mimic = false);
83
84 ///
85 /// \brief Build the model from a URDF model with a particular joint as root of the model tree
86 /// inside the model given as reference argument.
87 ///
88 /// \param[in] urdfTree the tree build from the URDF
89 /// \param[in] rootJoint The joint at the root of the model tree.
90 /// \param[in] mimic Parsing joints as mimic or not.
91 /// \param[in] verbose Print parsing info.
92 /// \param[out] model Reference model where to put the parsed information.
93 /// \return Return the reference on argument model for convenience.
94 ///
95 /// \note urdfTree can be build from ::urdf::parseURDF
96 /// or ::urdf::parseURDFFile
97 template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
98 ModelTpl<Scalar, Options, JointCollectionTpl> & buildModel(
99 const std::shared_ptr<::urdf::ModelInterface> urdfTree,
100 const typename ModelTpl<Scalar, Options, JointCollectionTpl>::JointModel & rootJoint,
101 ModelTpl<Scalar, Options, JointCollectionTpl> & model,
102 const bool verbose = false,
103 const bool mimic = false);
104
105 ///
106 /// \brief Build the model from a URDF model with a particular joint as root of the model tree
107 /// inside the model given as reference argument.
108 ///
109 /// \param[in] urdfTree the tree build from the URDF
110 /// \param[in] mimic Parsing joints as mimic or not.
111 /// \param[in] rootJoint The joint at the root of the model tree.
112 /// \param[in] rootJointName Name of the rootJoint.
113 /// \param[in] verbose Print parsing info.
114 /// \param[out] model Reference model where to put the parsed information.
115 /// \return Return the reference on argument model for convenience.
116 ///
117 /// \note urdfTree can be build from ::urdf::parseURDF
118 /// or ::urdf::parseURDFFile
119 template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
120 ModelTpl<Scalar, Options, JointCollectionTpl> & buildModel(
121 const std::shared_ptr<::urdf::ModelInterface> urdfTree,
122 const typename ModelTpl<Scalar, Options, JointCollectionTpl>::JointModel & rootJoint,
123 const std::string & rootJointName,
124 ModelTpl<Scalar, Options, JointCollectionTpl> & model,
125 const bool verbose = false,
126 const bool mimic = false);
127
128 ///
129 /// \brief Build the model from a URDF model
130 ///
131 /// \param[in] urdfTree the tree build from the URDF
132 /// \param[in] mimic Parsing joints as mimic or not.
133 /// \param[in] verbose Print parsing info.
134 /// \param[out] model Reference model where to put the parsed information.
135 /// \return Return the reference on argument model for convenience.
136 ///
137 /// \note urdfTree can be build from ::urdf::parseURDF
138 /// or ::urdf::parseURDFFile
139 template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
140 ModelTpl<Scalar, Options, JointCollectionTpl> & buildModel(
141 const std::shared_ptr<::urdf::ModelInterface> urdfTree,
142 ModelTpl<Scalar, Options, JointCollectionTpl> & model,
143 const bool verbose = false,
144 const bool mimic = false);
145
146 ///
147 /// \brief Build the model from an XML stream with a particular joint as root of the model tree
148 /// inside the model given as reference argument.
149 ///
150 /// \param[in] xml_stream stream containing the URDF model.
151 /// \param[in] rootJoint The joint at the root of the model tree.
152 /// \param[in] rootJointName Name of the rootJoint.
153 /// \param[in] mimic Parsing joints as mimic or not.
154 /// \param[in] verbose Print parsing info.
155 /// \param[out] model Reference model where to put the parsed information.
156 /// \return Return the reference on argument model for convenience.
157 ///
158 /// \note urdfTree can be build from ::urdf::parseURDF
159 /// or ::urdf::parseURDFFile
160 template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
161 ModelTpl<Scalar, Options, JointCollectionTpl> & buildModelFromXML(
162 const std::string & xml_stream,
163 const typename ModelTpl<Scalar, Options, JointCollectionTpl>::JointModel & rootJoint,
164 const std::string & rootJointName,
165 ModelTpl<Scalar, Options, JointCollectionTpl> & model,
166 const bool verbose = false,
167 const bool mimic = false);
168
169 ///
170 /// \brief Build the model from an XML stream with a particular joint as root of the model tree
171 /// inside the model given as reference argument.
172 ///
173 /// \param[in] xml_stream stream containing the URDF model.
174 /// \param[in] rootJoint The joint at the root of the model tree.
175 /// \param[in] verbose Print parsing info.
176 /// \param[in] mimic Parsing joints as mimic or not.
177 /// \param[out] model Reference model where to put the parsed information.
178 /// \return Return the reference on argument model for convenience.
179 ///
180 /// \note urdfTree can be build from ::urdf::parseURDF
181 /// or ::urdf::parseURDFFile
182 template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
183 ModelTpl<Scalar, Options, JointCollectionTpl> & buildModelFromXML(
184 const std::string & xml_stream,
185 const typename ModelTpl<Scalar, Options, JointCollectionTpl>::JointModel & rootJoint,
186 ModelTpl<Scalar, Options, JointCollectionTpl> & model,
187 const bool verbose = false,
188 const bool mimic = false);
189
190 ///
191 /// \brief Build the model from an XML stream
192 ///
193 /// \param[in] xml_stream stream containing the URDF model.
194 /// \param[in] mimic Parsing joints as mimic or not.
195 /// \param[in] verbose Print parsing info.
196 /// \param[out] model Reference model where to put the parsed information.
197 /// \return Return the reference on argument model for convenience.
198 ///
199 /// \note urdfTree can be build from ::urdf::parseURDF
200 /// or ::urdf::parseURDFFile
201 template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
202 ModelTpl<Scalar, Options, JointCollectionTpl> & buildModelFromXML(
203 const std::string & xml_stream,
204 ModelTpl<Scalar, Options, JointCollectionTpl> & model,
205 const bool verbose = false,
206 const bool mimic = false);
207
208 /**
209 * @brief Build The GeometryModel from a URDF file. Search for meshes
210 * in the directories specified by the user first and then in
211 * the environment variable ROS_PACKAGE_PATH
212 *
213 * @param[in] model The model of the robot, built with
214 * urdf::buildModel
215 * @param[in] filename The URDF complete (absolute) file path
216 * @param[in] package_paths A vector containing the different directories
217 * where to search for models and meshes, typically
218 * obtained from calling pinocchio::rosPaths()
219 *
220 * @param[in] type The type of objects that must be loaded (must be VISUAL or
221 * COLLISION)
222 * @param[in] mesh_loader object used to load meshes: hpp::fcl::MeshLoader [default] or
223 * hpp::fcl::CachedMeshLoader.
224 * @param[out] geom_model Reference where to put the parsed information.
225 *
226 * @return Returns the reference on geom model for convenience.
227 *
228 * \warning If hpp-fcl has not been found during compilation, COLLISION objects can not be
229 * loaded
230 *
231 */
232 template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
233 GeometryModel & buildGeom(
234 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
235 const std::string & filename,
236 const GeometryType type,
237 GeometryModel & geom_model,
238 const std::vector<std::string> & package_paths = std::vector<std::string>(),
239 ::hpp::fcl::MeshLoaderPtr mesh_loader = ::hpp::fcl::MeshLoaderPtr());
240
241 /**
242 * @brief Build The GeometryModel from a URDF file. Search for meshes
243 * in the directories specified by the user first and then in
244 * the environment variable ROS_PACKAGE_PATH
245 *
246 * @param[in] model The model of the robot, built with
247 * urdf::buildModel
248 * @param[in] filename The URDF complete (absolute) file path
249 * @param[in] package_path A string containing the path to the directories of the meshes,
250 * typically obtained from calling pinocchio::rosPaths().
251 *
252 * @param[in] type The type of objects that must be loaded (must be VISUAL or
253 * COLLISION)
254 * @param[in] mesh_loader object used to load meshes: hpp::fcl::MeshLoader [default] or
255 * hpp::fcl::CachedMeshLoader.
256 * @param[out] geom_model Reference where to put the parsed information.
257 *
258 * @return Returns the reference on geom model for convenience.
259 *
260 * \warning If hpp-fcl has not been found during compilation, COLLISION objects can not be
261 * loaded
262 *
263 */
264 template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
265 9 GeometryModel & buildGeom(
266 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
267 const std::string & filename,
268 const GeometryType type,
269 GeometryModel & geom_model,
270 const std::string & package_path,
271 hpp::fcl::MeshLoaderPtr mesh_loader = hpp::fcl::MeshLoaderPtr())
272
273 {
274
1/2
✓ Branch 2 taken 9 times.
✗ Branch 3 not taken.
9 const std::vector<std::string> dirs(1, package_path);
275
1/2
✓ Branch 2 taken 9 times.
✗ Branch 3 not taken.
18 return buildGeom(model, filename, type, geom_model, dirs, mesh_loader);
276 9 }
277
278 /**
279 * @brief Build The GeometryModel from a URDF model. Search for meshes
280 * in the directories specified by the user first and then in
281 * the environment variable ROS_PACKAGE_PATH
282 *
283 * @param[in] model The model of the robot, built with
284 * urdf::buildModel
285 * @param[in] xml_stream Stream containing the URDF model
286 * @param[in] package_paths A vector containing the different directories
287 * where to search for models and meshes, typically
288 * obtained from calling pinocchio::rosPaths()
289 *
290 * @param[in] type The type of objects that must be loaded (must be VISUAL or
291 * COLLISION)
292 * @param[in] mesh_loader object used to load meshes: hpp::fcl::MeshLoader [default] or
293 * hpp::fcl::CachedMeshLoader.
294 * @param[out] geom_model Reference where to put the parsed information.
295 *
296 * @return Returns the reference on geom model for convenience.
297 *
298 * \warning If hpp-fcl has not been found during compilation, COLLISION objects cannot be
299 * loaded
300 *
301 */
302 template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
303 GeometryModel & buildGeom(
304 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
305 const std::istream & xml_stream,
306 const GeometryType type,
307 GeometryModel & geom_model,
308 const std::vector<std::string> & package_paths = std::vector<std::string>(),
309 hpp::fcl::MeshLoaderPtr mesh_loader = hpp::fcl::MeshLoaderPtr());
310
311 /**
312 * @brief Build The GeometryModel from a URDF model. Search for meshes
313 * in the directories specified by the user first and then in
314 * the environment variable ROS_PACKAGE_PATH
315 *
316 * @param[in] model The model of the robot, built with
317 * urdf::buildModel
318 * @param[in] xml_stream Stream containing the URDF model
319 * @param[in] package_path A string containing the path to the directories of the meshes,
320 * typically obtained from calling pinocchio::rosPaths().
321 *
322 * @param[in] type The type of objects that must be loaded (must be VISUAL or
323 * COLLISION)
324 * @param[in] mesh_loader object used to load meshes: hpp::fcl::MeshLoader [default] or
325 * hpp::fcl::CachedMeshLoader.
326 * @param[out] geom_model Reference where to put the parsed information.
327 *
328 * @return Returns the reference on geom model for convenience.
329 *
330 * \warning If hpp-fcl has not been found during compilation, COLLISION objects cannot be
331 * loaded
332 *
333 */
334 template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
335 GeometryModel & buildGeom(
336 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
337 const std::istream & xml_stream,
338 const GeometryType type,
339 GeometryModel & geom_model,
340 const std::string & package_path,
341 hpp::fcl::MeshLoaderPtr mesh_loader = hpp::fcl::MeshLoaderPtr())
342
343 {
344 const std::vector<std::string> dirs(1, package_path);
345 return buildGeom(model, xml_stream, type, geom_model, dirs, mesh_loader);
346 }
347
348 } // namespace urdf
349 } // namespace pinocchio
350
351 #include "pinocchio/parsers/urdf/model.hxx"
352 #include "pinocchio/parsers/urdf/geometry.hxx"
353
354 #endif // ifndef __pinocchio_parsers_urdf_hpp__
355