GCC Code Coverage Report


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