urdf.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2015-2021 CNRS INRIA
3 //
4 
5 #include <iostream>
6 #include <fstream>
7 #include <streambuf>
8 
9 #include "pinocchio/multibody/model.hpp"
10 #include "pinocchio/parsers/urdf.hpp"
11 
12 #ifdef PINOCCHIO_WITH_HPP_FCL
14 #endif // PINOCCHIO_WITH_HPP_FCL
15 
16 #include <boost/test/unit_test.hpp>
17 
18 #include <urdf_parser/urdf_parser.h>
19 
20 
21 BOOST_AUTO_TEST_SUITE ( BOOST_TEST_MODULE )
22 
23 BOOST_AUTO_TEST_CASE ( build_model )
24 {
25  const std::string filename = PINOCCHIO_MODEL_DIR + std::string("/example-robot-data/robots/romeo_description/urdf/romeo_small.urdf");
26  const std::string dir = PINOCCHIO_MODEL_DIR;
27 
29  pinocchio::urdf::buildModel(filename, model);
30  pinocchio::GeometryModel geomModel;
31  pinocchio::urdf::buildGeom(model, filename, pinocchio::COLLISION, geomModel, dir);
32 
33  BOOST_CHECK(model.nq == 31);
34 }
35 
36 BOOST_AUTO_TEST_CASE ( build_model_simple_humanoid )
37 {
38  const std::string filename = PINOCCHIO_MODEL_DIR + std::string("/simple_humanoid.urdf");
39  const std::string dir = PINOCCHIO_MODEL_DIR;
40 
42  pinocchio::urdf::buildModel(filename, model);
43 
44  BOOST_CHECK_EQUAL(model.nq, 29);
45 
46  // Check that parsing collision_checking works.
47  pinocchio::GeometryModel geomModel;
48  pinocchio::urdf::buildGeom(model, filename, pinocchio::COLLISION, geomModel, dir);
49  BOOST_CHECK_EQUAL(geomModel.ngeoms, 2);
50 
51 #ifdef PINOCCHIO_WITH_HPP_FCL
52  // Check that cylinder is converted into capsule.
53 #ifdef PINOCCHIO_URDFDOM_COLLISION_WITH_GROUP_NAME
54  BOOST_CHECK_EQUAL(geomModel.geometryObjects[0].geometry->getNodeType(), hpp::fcl::GEOM_CYLINDER);
55 #else // PINOCCHIO_URDFDOM_COLLISION_WITH_GROUP_NAME
56  BOOST_CHECK_EQUAL(geomModel.geometryObjects[0].geometry->getNodeType(), hpp::fcl::GEOM_CAPSULE);
57 #endif
58 
59 #if ( HPP_FCL_MAJOR_VERSION>1 || ( HPP_FCL_MAJOR_VERSION==1 && \
60  ( HPP_FCL_MINOR_VERSION>1 || ( HPP_FCL_MINOR_VERSION==1 && \
61  HPP_FCL_PATCH_VERSION>3))))
62 # define PINOCCHIO_HPP_FCL_SUPERIOR_TO_1_1_3
63 #endif
64 
65 #if defined(PINOCCHIO_HPP_FCL_SUPERIOR_TO_1_1_3) && !defined(PINOCCHIO_URDFDOM_COLLISION_WITH_GROUP_NAME)
66  BOOST_CHECK_EQUAL(geomModel.geometryObjects[1].geometry->getNodeType(), hpp::fcl::GEOM_CONVEX);
67 #undef PINOCCHIO_HPP_FCL_SUPERIOR_TO_1_1_3
68 #else // PINOCCHIO_HPP_FCL_SUPERIOR_TO_1_1_3 && !PINOCCHIO_URDFDOM_COLLISION_WITH_GROUP_NAME
69  BOOST_CHECK_EQUAL(geomModel.geometryObjects[1].geometry->getObjectType(), hpp::fcl::OT_BVH);
70 #endif // PINOCCHIO_HPP_FCL_SUPERIOR_TO_1_1_3 && !PINOCCHIO_URDFDOM_COLLISION_WITH_GROUP_NAME
71 #endif // PINOCCHIO_WITH_HPP_FCL
72 
73  pinocchio::Model model_ff;
75 
76  BOOST_CHECK(model_ff.nq == 36);
77 }
78 
79 BOOST_AUTO_TEST_CASE ( check_mesh_relative_path )
80 {
81  std::string filename = PINOCCHIO_MODEL_DIR + std::string("/simple_humanoid.urdf");
82  const std::string dir = PINOCCHIO_MODEL_DIR;
83 
84  pinocchio::Model model0;
85  pinocchio::urdf::buildModel(filename, model0);
86  pinocchio::GeometryModel geomModel0;
87  pinocchio::urdf::buildGeom(model0, filename, pinocchio::COLLISION, geomModel0, dir);
88  BOOST_CHECK_EQUAL(geomModel0.ngeoms, 2);
89 
90  // check if urdf with relative mesh path without //package can be loaded
91  filename = PINOCCHIO_MODEL_DIR + std::string("/simple_humanoid_rel_mesh.urdf");
93  pinocchio::urdf::buildModel(filename, model1);
94  pinocchio::GeometryModel geomModel1;
95  pinocchio::urdf::buildGeom(model1, filename, pinocchio::COLLISION, geomModel1, dir);
96  BOOST_CHECK_EQUAL(geomModel1.ngeoms, 2);
97 
98  BOOST_CHECK_EQUAL(geomModel0.geometryObjects[1].name.compare(geomModel1.geometryObjects[1].name), 0);
99 }
100 
101 BOOST_AUTO_TEST_CASE ( build_model_from_XML )
102 {
103  const std::string filename = PINOCCHIO_MODEL_DIR + std::string("/example-robot-data/robots/romeo_description/urdf/romeo_small.urdf");
104 
105  // Read file as XML
106  std::ifstream file;
107  file.open(filename.c_str());
108  std::string filestr((std::istreambuf_iterator<char>(file)),
109  std::istreambuf_iterator<char>());
110 
112  pinocchio::urdf::buildModelFromXML(filestr, model);
113 
114  BOOST_CHECK(model.nq == 31);
115 }
116 
117 BOOST_AUTO_TEST_CASE ( check_tree_from_XML )
118 {
119  // Read file as XML
120  std::string filestr(
121  "<?xml version=\"1.0\" encoding=\"utf-8\"?>"
122  "<robot name=\"test\">"
123  " <link name=\"base_link\"/>"
124  " <link name=\"link_1\"/>"
125  " <link name=\"link_2\"/>"
126  " <joint name=\"joint_1\" type=\"fixed\">"
127  " <origin xyz=\"1 0 0\"/>"
128  " <axis xyz=\"0 0 1\"/>"
129  " <parent link=\"base_link\"/>"
130  " <child link=\"link_1\"/>"
131  " </joint>"
132  " <joint name=\"joint_2\" type=\"fixed\">"
133  " <origin xyz=\"0 1 0\"/>"
134  " <axis xyz=\"0 0 1\"/>"
135  " <parent link=\"link_1\"/>"
136  " <child link=\"link_2\"/>"
137  " </joint>"
138  "</robot>"
139  );
140 
142  pinocchio::urdf::buildModelFromXML(filestr, model);
143 
145  base_link_id = model.getFrameId("base_link"),
146  link1_id = model.getFrameId("link_1"),
147  link2_id = model.getFrameId("link_2"),
148  joint1_id = model.getFrameId("joint_1"),
149  joint2_id = model.getFrameId("joint_2");
150 
151  BOOST_CHECK_EQUAL(base_link_id, model.frames[joint1_id].previousFrame);
152  BOOST_CHECK_EQUAL(joint1_id , model.frames[link1_id ].previousFrame);
153  BOOST_CHECK_EQUAL(link1_id , model.frames[joint2_id].previousFrame);
154  BOOST_CHECK_EQUAL(joint2_id , model.frames[link2_id ].previousFrame);
155 }
156 
157 BOOST_AUTO_TEST_CASE ( build_model_from_UDRFTree )
158 {
159  const std::string filename = PINOCCHIO_MODEL_DIR + std::string("/example-robot-data/robots/romeo_description/urdf/romeo_small.urdf");
160 
161  ::urdf::ModelInterfaceSharedPtr urdfTree = ::urdf::parseURDFFile(filename);
162 
164  pinocchio::urdf::buildModel(urdfTree, model);
165 
166  BOOST_CHECK(model.nq == 31);
167 }
168 
169 BOOST_AUTO_TEST_CASE ( build_model_with_joint )
170 {
171  const std::string filename = PINOCCHIO_MODEL_DIR + std::string("/example-robot-data/robots/romeo_description/urdf/romeo_small.urdf");
172  const std::string dir = PINOCCHIO_MODEL_DIR;
173 
176  pinocchio::GeometryModel geomModel_collision, geomModel_visual;
177  pinocchio::urdf::buildGeom(model, filename, pinocchio::COLLISION, geomModel_collision, dir);
178  pinocchio::urdf::buildGeom(model, filename, pinocchio::VISUAL, geomModel_visual, dir);
179 
180  BOOST_CHECK(model.nq == 38);
181 }
182 
183 BOOST_AUTO_TEST_CASE ( build_model_with_joint_from_XML )
184 {
185  const std::string filename = PINOCCHIO_MODEL_DIR + std::string("/example-robot-data/robots/romeo_description/urdf/romeo_small.urdf");
186 
187  // Read file as XML
188  std::ifstream file;
189  file.open(filename.c_str());
190  std::string filestr((std::istreambuf_iterator<char>(file)),
191  std::istreambuf_iterator<char>());
192 
195 
196  BOOST_CHECK(model.nq == 38);
197 }
198 
199 BOOST_AUTO_TEST_CASE ( build_model_with_joint_from_UDRFTree )
200 {
201  const std::string filename = PINOCCHIO_MODEL_DIR + std::string("/example-robot-data/robots/romeo_description/urdf/romeo_small.urdf");
202 
203  ::urdf::ModelInterfaceSharedPtr urdfTree = ::urdf::parseURDFFile(filename);
204 
207 
208  BOOST_CHECK(model.nq == 38);
209 }
210 
211 BOOST_AUTO_TEST_CASE(append_two_URDF_models)
212 {
213  const std::string filename = PINOCCHIO_MODEL_DIR + std::string("/simple_humanoid.urdf");
214 
216  pinocchio::urdf::buildModel(filename, model);
217 
218  BOOST_CHECK(model.njoints == 30);
219  const int nframes = model.nframes;
220  const std::string filestr(
221  "<?xml version=\"1.0\" encoding=\"utf-8\"?>"
222  "<robot name=\"test\">"
223  " <link name=\"box\"/>"
224  "</robot>"
225  );
226 
227  pinocchio::urdf::buildModelFromXML(filestr, model);
228  BOOST_CHECK(model.njoints == 30);
229  BOOST_CHECK(nframes + 1 == model.nframes);
230 }
231 
232 BOOST_AUTO_TEST_CASE(append_two_URDF_models_with_root_joint)
233 {
234  const std::string filename = PINOCCHIO_MODEL_DIR + std::string("/simple_humanoid.urdf");
235 
238 
239  BOOST_CHECK(model.njoints == 31);
240  const std::string filestr(
241  "<?xml version=\"1.0\" encoding=\"utf-8\"?>"
242  "<robot name=\"test\">"
243  " <link name=\"box\"/>"
244  "</robot>"
245  );
246 
247 
248  BOOST_CHECK_THROW(pinocchio::urdf::buildModelFromXML(filestr, pinocchio::JointModelFreeFlyer(), model),
249  std::invalid_argument);
250 }
251 
252 BOOST_AUTO_TEST_CASE(check_specific_models)
253 {
254  const std::string filename = PINOCCHIO_MODEL_DIR + std::string("/baxter_simple.urdf");
255 
257  pinocchio::urdf::buildModel(filename, model);
258 }
259 
260 BOOST_AUTO_TEST_CASE(test_getFrameId_identical_link_and_joint_name)
261 {
262  // This test checks whether the input argument of getFrameId raises an exception when multiple frames with identical names are found.
263  // Note, a model that contains a link and a joint with the same name is valid, but the look-up for e.g. getFrameId requires the explicit
264  // specification of the FrameType in order to be valid.
265  // It resolved https://github.com/stack-of-tasks/pinocchio/issues/1771
267  const std::string filename = PINOCCHIO_MODEL_DIR + std::string("/../unittest/models/link_and_joint_identical_name.urdf");
268  pinocchio::urdf::buildModel(filename,model);
269 
270  BOOST_CHECK_THROW(model.getFrameId("base"), std::invalid_argument);
271  BOOST_CHECK(model.getFrameId("base", pinocchio::FrameType::BODY) == 2);
272  BOOST_CHECK(model.getFrameId("base", pinocchio::FrameType::FIXED_JOINT) == 3);
273 }
274 
275 BOOST_AUTO_TEST_SUITE_END()
int njoints
Number of joints.
FrameVector frames
Vector of operational frames registered on the model.
fixed joint frame: joint frame but for a fixed joint
#define PINOCCHIO_MODEL_DIR
int nframes
Number of operational frames.
body frame: attached to the collision, inertial or visual properties of a link
GeometryModel & buildGeom(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const std::string &filename, const GeometryType type, GeometryModel &geom_model, const std::vector< std::string > &package_paths=std::vector< std::string >(), ::hpp::fcl::MeshLoaderPtr mesh_loader=::hpp::fcl::MeshLoaderPtr())
Build The GeometryModel from a URDF file. Search for meshes in the directories specified by the user ...
GeometryObjectVector geometryObjects
Vector of GeometryObjects used for collision computations.
FrameIndex getFrameId(const std::string &name, const FrameType &type=(FrameType)(JOINT|FIXED_JOINT|BODY|OP_FRAME|SENSOR)) const
Returns the index of a frame given by its name.
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModel(const std::string &filename, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel &rootJoint, ModelTpl< Scalar, Options, JointCollectionTpl > &model, const bool verbose=false)
Build the model from a URDF file with a particular joint as root of the model tree inside the model g...
Index ngeoms
The number of GeometryObjects.
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModelFromXML(const std::string &xml_stream, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel &rootJoint, ModelTpl< Scalar, Options, JointCollectionTpl > &model, const bool verbose=false)
Build the model from an XML stream with a particular joint as root of the model tree inside the model...
BOOST_AUTO_TEST_CASE(build_model)
Definition: urdf.cpp:23
filename
int nq
Dimension of the configuration vector representation.


pinocchio
Author(s):
autogenerated on Fri Jun 23 2023 02:38:33