GCC Code Coverage Report
Directory: ./ Exec Total Coverage
File: unittest/urdf.cpp Lines: 128 128 100.0 %
Date: 2024-04-26 13:14:21 Branches: 696 1416 49.2 %

Line Branch Exec Source
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
13
#include <hpp/fcl/collision_object.h>
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
















4
BOOST_AUTO_TEST_CASE ( build_model )
24
{
25

6
  const std::string filename = PINOCCHIO_MODEL_DIR + std::string("/example-robot-data/robots/romeo_description/urdf/romeo_small.urdf");
26
4
  const std::string dir = PINOCCHIO_MODEL_DIR;
27
28
4
  pinocchio::Model model;
29
2
  pinocchio::urdf::buildModel(filename, model);
30
4
  pinocchio::GeometryModel geomModel;
31
2
  pinocchio::urdf::buildGeom(model, filename, pinocchio::COLLISION, geomModel, dir);
32
33



2
  BOOST_CHECK(model.nq == 31);
34
2
}
35
36
















4
BOOST_AUTO_TEST_CASE ( build_model_simple_humanoid )
37
{
38

6
  const std::string filename = PINOCCHIO_MODEL_DIR + std::string("/simple_humanoid.urdf");
39
4
  const std::string dir = PINOCCHIO_MODEL_DIR;
40
41
4
  pinocchio::Model model;
42
2
  pinocchio::urdf::buildModel(filename, model);
43
44


2
  BOOST_CHECK_EQUAL(model.nq, 29);
45
46
  // Check that parsing collision_checking works.
47
4
  pinocchio::GeometryModel geomModel;
48
2
  pinocchio::urdf::buildGeom(model, filename, pinocchio::COLLISION, geomModel, dir);
49


2
  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



2
  BOOST_CHECK_EQUAL(geomModel.geometryObjects[0].geometry->getNodeType(), hpp::fcl::GEOM_CAPSULE);
57
#endif
58
59
#ifndef PINOCCHIO_URDFDOM_COLLISION_WITH_GROUP_NAME
60



2
  BOOST_CHECK_EQUAL(geomModel.geometryObjects[1].geometry->getNodeType(), hpp::fcl::GEOM_CONVEX);
61
#else // PINOCCHIO_URDFDOM_COLLISION_WITH_GROUP_NAME
62
  BOOST_CHECK_EQUAL(geomModel.geometryObjects[1].geometry->getObjectType(), hpp::fcl::OT_BVH);
63
#endif
64
#endif // PINOCCHIO_WITH_HPP_FCL
65
66
4
  pinocchio::Model model_ff;
67

2
  pinocchio::urdf::buildModel(filename, pinocchio::JointModelFreeFlyer(), model_ff);
68
69



2
  BOOST_CHECK(model_ff.nq == 36);
70
2
}
71
72
















4
BOOST_AUTO_TEST_CASE ( check_mesh_relative_path )
73
{
74

6
  std::string filename = PINOCCHIO_MODEL_DIR + std::string("/simple_humanoid.urdf");
75
4
  const std::string dir = PINOCCHIO_MODEL_DIR;
76
77
4
  pinocchio::Model model0;
78
2
  pinocchio::urdf::buildModel(filename, model0);
79
4
  pinocchio::GeometryModel geomModel0;
80
2
  pinocchio::urdf::buildGeom(model0, filename, pinocchio::COLLISION, geomModel0, dir);
81


2
  BOOST_CHECK_EQUAL(geomModel0.ngeoms, 2);
82
83
  // check if urdf with relative mesh path without //package can be loaded
84

2
  filename = PINOCCHIO_MODEL_DIR + std::string("/simple_humanoid_rel_mesh.urdf");
85
4
  pinocchio::Model model1;
86
2
  pinocchio::urdf::buildModel(filename, model1);
87
4
  pinocchio::GeometryModel geomModel1;
88
2
  pinocchio::urdf::buildGeom(model1, filename, pinocchio::COLLISION, geomModel1, dir);
89


2
  BOOST_CHECK_EQUAL(geomModel1.ngeoms, 2);
90
91



2
  BOOST_CHECK_EQUAL(geomModel0.geometryObjects[1].name.compare(geomModel1.geometryObjects[1].name), 0);
92
2
}
93
94
















4
BOOST_AUTO_TEST_CASE ( build_model_from_XML )
95
{
96

6
  const std::string filename = PINOCCHIO_MODEL_DIR + std::string("/example-robot-data/robots/romeo_description/urdf/romeo_small.urdf");
97
98
  // Read file as XML
99
4
  std::ifstream file;
100
2
  file.open(filename.c_str());
101
  std::string filestr((std::istreambuf_iterator<char>(file)),
102
4
                      std::istreambuf_iterator<char>());
103
104
4
  pinocchio::Model model;
105
2
  pinocchio::urdf::buildModelFromXML(filestr, model);
106
107



2
  BOOST_CHECK(model.nq == 31);
108
2
}
109
110
















4
BOOST_AUTO_TEST_CASE ( check_tree_from_XML )
111
{
112
  // Read file as XML
113
  std::string filestr(
114
      "<?xml version=\"1.0\" encoding=\"utf-8\"?>"
115
      "<robot name=\"test\">"
116
      "  <link name=\"base_link\"/>"
117
      "  <link name=\"link_1\"/>"
118
      "  <link name=\"link_2\"/>"
119
      "  <joint name=\"joint_1\" type=\"fixed\">"
120
      "    <origin xyz=\"1 0 0\"/>"
121
      "    <axis xyz=\"0 0 1\"/>"
122
      "    <parent link=\"base_link\"/>"
123
      "    <child link=\"link_1\"/>"
124
      "  </joint>"
125
      "  <joint name=\"joint_2\" type=\"fixed\">"
126
      "    <origin xyz=\"0 1 0\"/>"
127
      "    <axis xyz=\"0 0 1\"/>"
128
      "    <parent link=\"link_1\"/>"
129
      "    <child link=\"link_2\"/>"
130
      "  </joint>"
131
      "</robot>"
132
4
      );
133
134
4
  pinocchio::Model model;
135
2
  pinocchio::urdf::buildModelFromXML(filestr, model);
136
137
  pinocchio::JointIndex
138

2
    base_link_id = model.getFrameId("base_link"),
139

2
    link1_id     = model.getFrameId("link_1"),
140

2
    link2_id     = model.getFrameId("link_2"),
141

2
    joint1_id    = model.getFrameId("joint_1"),
142

2
    joint2_id    = model.getFrameId("joint_2");
143
144


2
  BOOST_CHECK_EQUAL(base_link_id, model.frames[joint1_id].previousFrame);
145


2
  BOOST_CHECK_EQUAL(joint1_id   , model.frames[link1_id ].previousFrame);
146


2
  BOOST_CHECK_EQUAL(link1_id    , model.frames[joint2_id].previousFrame);
147


2
  BOOST_CHECK_EQUAL(joint2_id   , model.frames[link2_id ].previousFrame);
148
2
}
149
150
















4
BOOST_AUTO_TEST_CASE ( build_model_from_UDRFTree )
151
{
152

6
  const std::string filename = PINOCCHIO_MODEL_DIR + std::string("/example-robot-data/robots/romeo_description/urdf/romeo_small.urdf");
153
154
4
  ::urdf::ModelInterfaceSharedPtr urdfTree = ::urdf::parseURDFFile(filename);
155
156
4
  pinocchio::Model model;
157
2
  pinocchio::urdf::buildModel(urdfTree, model);
158
159



2
  BOOST_CHECK(model.nq == 31);
160
2
}
161
162
















4
BOOST_AUTO_TEST_CASE ( build_model_with_joint )
163
{
164

6
  const std::string filename = PINOCCHIO_MODEL_DIR + std::string("/example-robot-data/robots/romeo_description/urdf/romeo_small.urdf");
165
4
  const std::string dir = PINOCCHIO_MODEL_DIR;
166
167
4
  pinocchio::Model model;
168

2
  pinocchio::urdf::buildModel(filename, pinocchio::JointModelFreeFlyer(), model);
169

4
  pinocchio::GeometryModel geomModel_collision, geomModel_visual;
170
2
  pinocchio::urdf::buildGeom(model, filename, pinocchio::COLLISION, geomModel_collision, dir);
171
2
  pinocchio::urdf::buildGeom(model, filename, pinocchio::VISUAL, geomModel_visual, dir);
172
173



2
  BOOST_CHECK(model.nq == 38);
174
2
}
175
176
















4
BOOST_AUTO_TEST_CASE ( build_model_with_joint_from_XML )
177
{
178

6
  const std::string filename = PINOCCHIO_MODEL_DIR + std::string("/example-robot-data/robots/romeo_description/urdf/romeo_small.urdf");
179
180
  // Read file as XML
181
4
  std::ifstream file;
182
2
  file.open(filename.c_str());
183
  std::string filestr((std::istreambuf_iterator<char>(file)),
184
4
                      std::istreambuf_iterator<char>());
185
186
4
  pinocchio::Model model;
187

2
  pinocchio::urdf::buildModelFromXML(filestr, pinocchio::JointModelFreeFlyer(), model);
188
189



2
  BOOST_CHECK(model.nq == 38);
190
2
}
191
192
















4
BOOST_AUTO_TEST_CASE ( build_model_with_joint_from_UDRFTree )
193
{
194

6
  const std::string filename = PINOCCHIO_MODEL_DIR + std::string("/example-robot-data/robots/romeo_description/urdf/romeo_small.urdf");
195
196
4
  ::urdf::ModelInterfaceSharedPtr urdfTree = ::urdf::parseURDFFile(filename);
197
198
4
  pinocchio::Model model;
199

2
  pinocchio::urdf::buildModel(urdfTree, pinocchio::JointModelFreeFlyer(), model);
200
201



2
  BOOST_CHECK(model.nq == 38);
202
2
}
203
204
















4
BOOST_AUTO_TEST_CASE(append_two_URDF_models)
205
{
206

6
  const std::string filename = PINOCCHIO_MODEL_DIR + std::string("/simple_humanoid.urdf");
207
208
4
  pinocchio::Model model;
209
2
  pinocchio::urdf::buildModel(filename, model);
210
211



2
  BOOST_CHECK(model.njoints == 30);
212
2
  const int nframes = model.nframes;
213
  const std::string filestr(
214
                            "<?xml version=\"1.0\" encoding=\"utf-8\"?>"
215
                            "<robot name=\"test\">"
216
                            "  <link name=\"box\"/>"
217
                            "</robot>"
218
4
                            );
219
220
2
  pinocchio::urdf::buildModelFromXML(filestr, model);
221



2
  BOOST_CHECK(model.njoints == 30);
222



2
  BOOST_CHECK(nframes + 1 == model.nframes);
223
2
}
224
225
















4
BOOST_AUTO_TEST_CASE(append_two_URDF_models_with_root_joint)
226
{
227

6
  const std::string filename = PINOCCHIO_MODEL_DIR + std::string("/simple_humanoid.urdf");
228
229
4
  pinocchio::Model model;
230

2
  pinocchio::urdf::buildModel(filename, pinocchio::JointModelFreeFlyer(), model);
231
232



2
  BOOST_CHECK(model.njoints == 31);
233
  const std::string filestr(
234
                            "<?xml version=\"1.0\" encoding=\"utf-8\"?>"
235
                            "<robot name=\"test\">"
236
                            "  <link name=\"box\"/>"
237
                            "</robot>"
238
6
                            );
239
240
241









8
  BOOST_CHECK_THROW(pinocchio::urdf::buildModelFromXML(filestr, pinocchio::JointModelFreeFlyer(), model),
242
                    std::invalid_argument);
243
2
}
244
245
















4
BOOST_AUTO_TEST_CASE(check_specific_models)
246
{
247

6
  const std::string filename = PINOCCHIO_MODEL_DIR + std::string("/baxter_simple.urdf");
248
249
4
  pinocchio::Model model;
250
2
  pinocchio::urdf::buildModel(filename, model);
251
2
}
252
253
















4
BOOST_AUTO_TEST_CASE(test_getFrameId_identical_link_and_joint_name)
254
{
255
    // This test checks whether the input argument of getFrameId raises an exception when multiple frames with identical names are found.
256
    // 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
257
    // specification of the FrameType in order to be valid.
258
    // It resolved https://github.com/stack-of-tasks/pinocchio/issues/1771
259
4
    pinocchio::Model model;
260

6
    const std::string filename = PINOCCHIO_MODEL_DIR + std::string("/../unittest/models/link_and_joint_identical_name.urdf");
261
2
    pinocchio::urdf::buildModel(filename,model);
262
263








10
    BOOST_CHECK_THROW(model.getFrameId("base"), std::invalid_argument);
264




2
    BOOST_CHECK(model.getFrameId("base", pinocchio::FrameType::BODY) == 2);
265




2
    BOOST_CHECK(model.getFrameId("base", pinocchio::FrameType::FIXED_JOINT) == 3);
266
2
}
267
268
BOOST_AUTO_TEST_SUITE_END()