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