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