tesseract_urdf_urdf_unit.cpp
Go to the documentation of this file.
3 #include <gtest/gtest.h>
4 #include <Eigen/Geometry>
7 
13 
14 TEST(TesseractURDFUnit, parse_urdf) // NOLINT
15 {
17  {
18  std::string str =
19  R"(<robot name="test" extra="0 0 0" tesseract:make_convex="true">
20  <joint name="j1" type="fixed">
21  <parent link="l1"/>
22  <child link="l2"/>
23  <origin xyz="0 0 0" rpy="0 0 0"/>
24  <dynamics damping="87.098" friction="3.1290"/>
25  <limit lower="12.34" upper="22.999" effort="99.0" velocity="23.0"/>
26  <safety_controller soft_lower_limit="8.765" soft_upper_limit="9.003" k_position="7.0034" k_velocity="9.998"/>
27  <calibration rising="8.654" falling="0.0445"/>
28  <mimic joint="j2" multiplier="9.87" offset="0.098"/>
29  </joint>
30  <link name="l1"/>
31  <link name="l2"/>
32  </robot>)";
34  EXPECT_TRUE(sg != nullptr);
35  EXPECT_TRUE(sg->getName() == "test");
36  EXPECT_TRUE(sg->isTree());
37  EXPECT_TRUE(sg->isAcyclic());
38  EXPECT_TRUE(sg->getJoints().size() == 1);
39  EXPECT_TRUE(sg->getLinks().size() == 2);
40  }
41 
42  {
43  std::string str =
44  R"(<robot name="test" extra="0 0 0" tesseract:make_convex="true">
45  <joint name="j1" type="fixed">
46  <parent link="l1"/>
47  <child link="l2"/>
48  <origin xyz="0 0 0" rpy="0 0 0"/>
49  <dynamics damping="87.098" friction="3.1290"/>
50  <limit lower="12.34" upper="22.999" effort="99.0" velocity="23.0"/>
51  <safety_controller soft_lower_limit="8.765" soft_upper_limit="9.003" k_position="7.0034" k_velocity="9.998"/>
52  <calibration rising="8.654" falling="0.0445"/>
53  <mimic joint="j2" multiplier="9.87" offset="0.098"/>
54  </joint>
55  <link name="l1"/>
56  <link name="l2"/>
57  </robot>)";
59  EXPECT_TRUE(sg != nullptr);
60  EXPECT_TRUE(sg->getName() == "test");
61  EXPECT_TRUE(sg->isTree());
62  EXPECT_TRUE(sg->isAcyclic());
63  EXPECT_TRUE(sg->getJoints().size() == 1);
64  EXPECT_TRUE(sg->getLinks().size() == 2);
65  }
66 
67  {
68  std::string str =
69  R"(<robot name="test" tesseract:make_convex="true">
70  <joint name="j1" type="fixed">
71  <parent link="l1"/>
72  <child link="l2"/>
73  <origin xyz="0 0 0" rpy="0 0 0"/>
74  <dynamics damping="87.098" friction="3.1290"/>
75  <limit lower="12.34" upper="22.999" effort="99.0" velocity="23.0"/>
76  <safety_controller soft_lower_limit="8.765" soft_upper_limit="9.003" k_position="7.0034" k_velocity="9.998"/>
77  <calibration rising="8.654" falling="0.0445"/>
78  <mimic joint="j2" multiplier="9.87" offset="0.098"/>
79  </joint>
80  <joint name="j2" type="fixed">
81  <parent link="l1"/>
82  <child link="l2"/>
83  </joint>
84  <link name="l1"/>
85  <link name="l2"/>
86  </robot>)";
87  EXPECT_ANY_THROW(tesseract_urdf::parseURDFString(str, resource_locator)); // NOLINT
88  }
89 
90  {
91  std::string str =
92  R"(<robot name="test" tesseract:make_convex="true">
93  <joint name="j1" type="fixed">
94  <parent link="l1"/>
95  <child link="l2"/>
96  <origin xyz="0 0 0" rpy="0 0 0"/>
97  <dynamics damping="87.098" friction="3.1290"/>
98  <limit lower="12.34" upper="22.999" effort="99.0" velocity="23.0"/>
99  <safety_controller soft_lower_limit="8.765" soft_upper_limit="9.003" k_position="7.0034" k_velocity="9.998"/>
100  <calibration rising="8.654" falling="0.0445"/>
101  <mimic joint="j2" multiplier="9.87" offset="0.098"/>
102  </joint>
103  <joint name="j2" type="fixed">
104  <parent link="l1"/>
105  <child link="l2"/>
106  </joint>
107  <link name="l1"/>
108  <link name="l2"/>
109  </robot>)";
110  EXPECT_ANY_THROW(tesseract_urdf::parseURDFString(str, resource_locator)); // NOLINT
111  }
112 
113  {
114  std::string str =
115  R"(<robot name="test" tesseract:make_convex="true">
116  <joint name="j1" type="fixed">
117  <parent link="l1"/>
118  <child link="l2"/>
119  <origin xyz="0 0 0" rpy="0 0 0"/>
120  <dynamics damping="87.098" friction="3.1290"/>
121  <limit lower="12.34" upper="22.999" effort="99.0" velocity="23.0"/>
122  <safety_controller soft_lower_limit="8.765" soft_upper_limit="9.003" k_position="7.0034" k_velocity="9.998"/>
123  <calibration rising="8.654" falling="0.0445"/>
124  <mimic joint="j2" multiplier="9.87" offset="0.098"/>
125  </joint>
126  <link name="l1"/>
127  <link name="l3"/>
128  </robot>)";
129  EXPECT_ANY_THROW(tesseract_urdf::parseURDFString(str, resource_locator)); // NOLINT
130  }
131 
132  {
133  std::string str =
134  R"(<robot name="test" tesseract:make_convex="true">
135  <joint name="j1" type="fixed">
136  <parent link="l1"/>
137  <child link="l2"/>
138  <origin xyz="0 0 0" rpy="0 0 0"/>
139  <dynamics damping="87.098" friction="3.1290"/>
140  <limit lower="12.34" upper="22.999" effort="99.0" velocity="23.0"/>
141  <safety_controller soft_lower_limit="8.765" soft_upper_limit="9.003" k_position="7.0034" k_velocity="9.998"/>
142  <calibration rising="8.654" falling="0.0445"/>
143  <mimic joint="j2" multiplier="9.87" offset="0.098"/>
144  </joint>
145  <link name="l1"/>
146  <link name="l2"/>
147  <link name="l3"/>
148  </robot>)";
149  EXPECT_ANY_THROW(tesseract_urdf::parseURDFString(str, resource_locator)); // NOLINT
150  }
151 
152  {
153  std::string str =
154  R"(<robot name="test" tesseract:make_convex="true">
155  <joint name="j1" type="fixed">
156  <parent link="l1"/>
157  <child link="l3"/>
158  <origin xyz="0 0 0" rpy="0 0 0"/>
159  <dynamics damping="87.098" friction="3.1290"/>
160  <limit lower="12.34" upper="22.999" effort="99.0" velocity="23.0"/>
161  <safety_controller soft_lower_limit="8.765" soft_upper_limit="9.003" k_position="7.0034" k_velocity="9.998"/>
162  <calibration rising="8.654" falling="0.0445"/>
163  <mimic joint="j2" multiplier="9.87" offset="0.098"/>
164  </joint>
165  <link name="l1"/>
166  <link name="l2"/>
167  </robot>)";
168  EXPECT_ANY_THROW(tesseract_urdf::parseURDFString(str, resource_locator)); // NOLINT
169  }
170 
171  {
172  std::string str =
173  R"(<robot name="test" tesseract:make_convex="true">
174  <joint name="j1" type="fixed">
175  <parent link="l1"/>
176  <child link="l2"/>
177  <origin xyz="0 0 0" rpy="0 0 0"/>
178  <dynamics damping="87.098" friction="3.1290"/>
179  <limit lower="12.34" upper="22.999" effort="99.0" velocity="23.0"/>
180  <safety_controller soft_lower_limit="8.765" soft_upper_limit="9.003" k_position="7.0034" k_velocity="9.998"/>
181  <calibration rising="8.654" falling="0.0445"/>
182  <mimic joint="j2" multiplier="9.87" offset="0.098"/>
183  </joint>
184  <link name="l1"/>
185  <link name="l2"/>
186  <link name="l1"/>
187  </robot>)";
188  EXPECT_ANY_THROW(tesseract_urdf::parseURDFString(str, resource_locator)); // NOLINT
189  }
190 
191  {
192  std::string str =
193  R"(<robot tesseract:make_convex="true">
194  <joint name="j1" type="fixed" >
195  <parent link="l1"/>
196  <child link="l2"/>
197  <origin xyz="0 0 0" rpy="0 0 0"/>
198  <dynamics damping="87.098" friction="3.1290"/>
199  <limit lower="12.34" upper="22.999" effort="99.0" velocity="23.0"/>
200  <safety_controller soft_lower_limit="8.765" soft_upper_limit="9.003" k_position="7.0034" k_velocity="9.998"/>
201  <calibration rising="8.654" falling="0.0445"/>
202  <mimic joint="j2" multiplier="9.87" offset="0.098"/>
203  </joint>
204  <link name="l1"/>
205  <link name="l2"/>
206  </robot>)";
207  EXPECT_ANY_THROW(tesseract_urdf::parseURDFString(str, resource_locator)); // NOLINT
208  }
209 
210  {
211  std::string str =
212  R"(<robot name="test" tesseract:make_convex="true">
213  <joint name="j1" type="fixed">
214  <parent link="l2"/>
215  <child link="l3"/>
216  <origin xyz="0 0 0" rpy="0 0 0"/>
217  <dynamics damping="87.098" friction="3.1290"/>
218  <limit lower="12.34" upper="22.999" effort="99.0" velocity="23.0"/>
219  <safety_controller soft_lower_limit="8.765" soft_upper_limit="9.003" k_position="7.0034" k_velocity="9.998"/>
220  <calibration rising="8.654" falling="0.0445"/>
221  <mimic joint="j2" multiplier="9.87" offset="0.098"/>
222  </joint>
223  <joint name="j1" type="fixed">
224  <parent link="l1"/>
225  <child link="l2"/>
226  </joint>
227  <link name="l1"/>
228  <link name="l2"/>
229  <link name="l3"/>
230  </robot>)";
231  EXPECT_ANY_THROW(tesseract_urdf::parseURDFString(str, resource_locator)); // NOLINT
232  }
233 
234  // Not a urdf
235  {
236  std::string str = R"(this is not a urdf)";
237  EXPECT_ANY_THROW(tesseract_urdf::parseURDFString(str, resource_locator)); // NOLINT
238  }
239 
240  // Missing robot element
241  {
242  std::string str = R"(<abcd name="test"></abcd>)";
243  EXPECT_ANY_THROW(tesseract_urdf::parseURDFString(str, resource_locator)); // NOLINT
244  }
245 
246  // Invalid version
247  {
248  std::string str = R"(<robot name="test" tesseract:make_convex="true" version="a"></robot>)";
249  EXPECT_ANY_THROW(tesseract_urdf::parseURDFString(str, resource_locator)); // NOLINT
250  }
251 
252  // Version not equal 1
253  {
254  std::string str = R"(<robot name="test" tesseract:make_convex="true" version="2"></robot>)";
255  EXPECT_ANY_THROW(tesseract_urdf::parseURDFString(str, resource_locator)); // NOLINT
256  }
257 
258  // Missing tesseract:make_convex attribute
259  {
260  std::string str = R"(<robot name="test"></robot>)";
261  EXPECT_ANY_THROW(tesseract_urdf::parseURDFString(str, resource_locator)); // NOLINT
262  }
263 
264  // The tesseract:make_convex attribute is not a bool
265  {
266  std::string str = R"(<robot name="test" tesseract:make_convex="1.5"></robot>)";
267  EXPECT_ANY_THROW(tesseract_urdf::parseURDFString(str, resource_locator)); // NOLINT
268  }
269 
270  {
271  const std::string path =
272  resource_locator.locateResource("package://tesseract_support/urdf/lbr_iiwa_14_r820.urdf")->getFilePath();
274  EXPECT_TRUE(sg != nullptr);
275  }
276 }
277 
278 TEST(TesseractURDFUnit, parse_urdf_with_available_materials) // NOLINT
279 {
281  {
282  std::string str =
283  R"(<robot name="test" extra="0 0 0" tesseract:make_convex="true">
284  <material name="test_material" extra="0 0 0">
285  <color rgba="1 .5 .5 1" extra="0 0 0"/>
286  </material>
287  <joint name="j1" type="fixed">
288  <parent link="l1"/>
289  <child link="l2"/>
290  <origin xyz="0 0 0" rpy="0 0 0"/>
291  <dynamics damping="87.098" friction="3.1290"/>
292  <limit lower="12.34" upper="22.999" effort="99.0" velocity="23.0"/>
293  <safety_controller soft_lower_limit="8.765" soft_upper_limit="9.003" k_position="7.0034" k_velocity="9.998"/>
294  <calibration rising="8.654" falling="0.0445"/>
295  <mimic joint="j2" multiplier="9.87" offset="0.098"/>
296  </joint>
297  <link name="l1">
298  <visual>
299  <origin xyz="0 0 0" rpy="0 0 0" />
300  <geometry>
301  <box size="1 1 1" />
302  </geometry>
303  <material name="test_material"/>
304  </visual>
305  </link>
306  <link name="l2"/>
307  </robot>)";
309  EXPECT_TRUE(sg != nullptr);
310  EXPECT_TRUE(sg->getName() == "test");
311  EXPECT_TRUE(sg->isTree());
312  EXPECT_TRUE(sg->isAcyclic());
313  EXPECT_TRUE(sg->getJoints().size() == 1);
314  EXPECT_TRUE(sg->getLinks().size() == 2);
315  EXPECT_EQ(sg->getLink("l1")->visual[0]->material->getName(), "test_material");
316  }
317 
318  {
319  std::string str =
320  R"(<robot name="test" extra="0 0 0" tesseract:make_convex="true">
321  <joint name="j1" type="fixed">
322  <parent link="l1"/>
323  <child link="l2"/>
324  <origin xyz="0 0 0" rpy="0 0 0"/>
325  <dynamics damping="87.098" friction="3.1290"/>
326  <limit lower="12.34" upper="22.999" effort="99.0" velocity="23.0"/>
327  <safety_controller soft_lower_limit="8.765" soft_upper_limit="9.003" k_position="7.0034" k_velocity="9.998"/>
328  <calibration rising="8.654" falling="0.0445"/>
329  <mimic joint="j2" multiplier="9.87" offset="0.098"/>
330  </joint>
331  <link name="l1">
332  <visual>
333  <origin xyz="0 0 0" rpy="0 0 0" />
334  <geometry>
335  <box size="1 1 1" />
336  </geometry>
337  <material name="test_material" extra="0 0 0">
338  <color rgba="1 .5 .5 1" extra="0 0 0"/>
339  </material>
340  </visual>
341  </link>
342  <link name="l2">
343  <visual>
344  <origin xyz="0 0 0" rpy="0 0 0" />
345  <geometry>
346  <box size="1 1 1" />
347  </geometry>
348  <material name="test_material" />
349  </visual>
350  </link>
351  </robot>)";
353  EXPECT_TRUE(sg != nullptr);
354  EXPECT_TRUE(sg->getName() == "test");
355  EXPECT_TRUE(sg->isTree());
356  EXPECT_TRUE(sg->isAcyclic());
357  EXPECT_TRUE(sg->getJoints().size() == 1);
358  EXPECT_TRUE(sg->getLinks().size() == 2);
359  EXPECT_EQ(sg->getLink("l1")->visual[0]->material->getName(), "test_material");
360  }
361 
362  {
363  std::string str =
364  R"(<robot name="test" extra="0 0 0" tesseract:make_convex="true">
365  <joint name="j1" type="fixed">
366  <parent link="l1"/>
367  <child link="l2"/>
368  <origin xyz="0 0 0" rpy="0 0 0"/>
369  <dynamics damping="87.098" friction="3.1290"/>
370  <limit lower="12.34" upper="22.999" effort="99.0" velocity="23.0"/>
371  <safety_controller soft_lower_limit="8.765" soft_upper_limit="9.003" k_position="7.0034" k_velocity="9.998"/>
372  <calibration rising="8.654" falling="0.0445"/>
373  <mimic joint="j2" multiplier="9.87" offset="0.098"/>
374  </joint>
375  <link name="l1">
376  <visual>
377  <origin xyz="0 0 0" rpy="0 0 0" />
378  <geometry>
379  <box size="1 1 1" />
380  </geometry>
381  <material name="test_material" />
382  </visual>
383  </link>
384  <link name="l2">
385  <visual>
386  <origin xyz="0 0 0" rpy="0 0 0" />
387  <geometry>
388  <box size="1 1 1" />
389  </geometry>
390  <material name="test_material" extra="0 0 0">
391  <color rgba="1 .5 .5 1" extra="0 0 0"/>
392  </material>
393  </visual>
394  </link>
395  </robot>)";
396  EXPECT_ANY_THROW(tesseract_urdf::parseURDFString(str, resource_locator)); // NOLINT
397  }
398 
399  {
400  std::string str =
401  R"(<robot name="test" extra="0 0 0" tesseract:make_convex="true">
402  <joint name="j1" type="fixed">
403  <parent link="l1"/>
404  <child link="l2"/>
405  <origin xyz="0 0 0" rpy="0 0 0"/>
406  <dynamics damping="87.098" friction="3.1290"/>
407  <limit lower="12.34" upper="22.999" effort="99.0" velocity="23.0"/>
408  <safety_controller soft_lower_limit="8.765" soft_upper_limit="9.003" k_position="7.0034" k_velocity="9.998"/>
409  <calibration rising="8.654" falling="0.0445"/>
410  <mimic joint="j2" multiplier="9.87" offset="0.098"/>
411  </joint>
412  <link name="l1">
413  <visual>
414  <origin xyz="0 0 0" rpy="0 0 0" />
415  <geometry>
416  <box size="1 1 1" />
417  </geometry>
418  <material name="test_material" extra="0 0 0">
419  <color rgba="1 .5 .5 1" extra="0 0 0"/>
420  </material>
421  </visual>
422  </link>
423  <link name="l2">
424  <visual>
425  <origin xyz="0 0 0" rpy="0 0 0" />
426  <geometry>
427  <box size="1 1 1" />
428  </geometry>
429  <material name="test_material" extra="0 0 0">
430  <color rgba="1 .5 .5 1" extra="0 0 0"/>
431  </material>
432  </visual>
433  </link>
434  </robot>)";
436  EXPECT_TRUE(sg != nullptr);
437  }
438 }
439 
440 TEST(TesseractURDFUnit, LoadURDFUnit) // NOLINT
441 {
442  using namespace tesseract_scene_graph;
443 
445  std::string urdf_file =
446  locator.locateResource("package://tesseract_support/urdf/lbr_iiwa_14_r820.urdf")->getFilePath();
447 
448  auto g = tesseract_urdf::parseURDFFile(urdf_file, locator);
449 
450  EXPECT_TRUE(g->getJoints().size() == 9);
451  EXPECT_TRUE(g->getLinks().size() == 10);
452  EXPECT_TRUE(g->isTree());
453  EXPECT_TRUE(g->isAcyclic());
454 
455  // Save Graph
456  g->saveDOT(tesseract_common::getTempPath() + "tesseract_urdf_import.dot");
457 
458  // Get Shortest Path
459  auto path = g->getShortestPath("link_1", "link_4");
460 
461  std::cout << path << "\n";
462  EXPECT_TRUE(path.links.size() == 4);
463  EXPECT_TRUE(std::find(path.links.begin(), path.links.end(), "link_1") != path.links.end());
464  EXPECT_TRUE(std::find(path.links.begin(), path.links.end(), "link_2") != path.links.end());
465  EXPECT_TRUE(std::find(path.links.begin(), path.links.end(), "link_3") != path.links.end());
466  EXPECT_TRUE(std::find(path.links.begin(), path.links.end(), "link_4") != path.links.end());
467  EXPECT_TRUE(path.joints.size() == 3);
468  EXPECT_TRUE(std::find(path.joints.begin(), path.joints.end(), "joint_a2") != path.joints.end());
469  EXPECT_TRUE(std::find(path.joints.begin(), path.joints.end(), "joint_a3") != path.joints.end());
470  EXPECT_TRUE(std::find(path.joints.begin(), path.joints.end(), "joint_a4") != path.joints.end());
471 }
472 
473 TEST(TesseractURDFUnit, write_urdf) // NOLINT
474 {
475  { // trigger nullptr input
477  bool success = true;
478  try
479  {
480  tesseract_urdf::writeURDFFile(sg, "/tmp/", "urdf0.urdf");
481  }
482  catch (...)
483  {
484  success = false;
485  }
486 
487  EXPECT_FALSE(success);
488  }
489 
490  { // Successful run
491  tesseract_scene_graph::SceneGraph::Ptr sg = std::make_shared<tesseract_scene_graph::SceneGraph>();
492 
493  // Add 2 links
494  tesseract_scene_graph::Link::Ptr link_0 = std::make_shared<tesseract_scene_graph::Link>("link_0");
495  tesseract_scene_graph::Link::Ptr link_1 = std::make_shared<tesseract_scene_graph::Link>("link_1");
496  sg->addLink(*link_0);
497  sg->addLink(*link_1);
498 
499  // Add joint
500  tesseract_scene_graph::Joint::Ptr joint_0 = std::make_shared<tesseract_scene_graph::Joint>("joint_0");
502  joint_0->parent_link_name = link_0->getName();
503  joint_0->child_link_name = link_1->getName();
504  sg->addJoint(*joint_0);
505 
506  bool success = true;
507  try
508  {
509  tesseract_urdf::writeURDFFile(sg, "/tmp/", "urdf1.urdf");
510  }
511  catch (...)
512  {
513  success = false;
514  }
515 
516  EXPECT_TRUE(success);
517  }
518 
519  /* Triggering a bad link is actually very difficult. The addLink function uses Link::clone(), which
520  * dereferences all the collision & visual pointers, causing a segfault if the link was ill-formed.
521  * This should probably get changed to throwing an exception if it is nullptr.
522  { // Trigger Bad Link
523  tesseract_scene_graph::SceneGraph::Ptr sg = std::make_shared<tesseract_scene_graph::SceneGraph>();
524 
525  // Add 2 links
526  tesseract_scene_graph::Link::Ptr link_0 = std::make_shared<tesseract_scene_graph::Link>("link_0");
527  link_0->visual.resize(1);
528  link_0->visual[0] = nullptr; // Bad visual geometry to cause write failure in link
529  tesseract_scene_graph::Link::Ptr link_1 = std::make_shared<tesseract_scene_graph::Link>("link_1");
530  sg->addLink(*link_0);
531  sg->addLink(*link_1);
532 
533  // Add joint
534  tesseract_scene_graph::Joint::Ptrros-industrial joint_0 = std::make_shared<tesseract_scene_graph::Joint>("joint_0");
535  joint_0->type = tesseract_scene_graph::JointType::FIXED;
536  joint_0->parent_link_name = link_0->getName();
537  joint_0->child_link_name = link_1->getName();
538  sg->addJoint(*joint_0);
539 
540  bool success = true;
541  try
542  {
543  tesseract_urdf::writeURDFFile(sg, "/tmp/", "urdf3.urdf");
544  }
545  catch (...)
546  {
547  success = false;
548  }
549 
550  EXPECT_FALSE(success);
551  }
552  */
553 }
graph.h
tesseract_common::getTempPath
std::string getTempPath()
utils.h
resource_locator.h
joint.h
TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
EXPECT_TRUE
#define EXPECT_TRUE(args)
tesseract_urdf::parseURDFFile
std::unique_ptr< tesseract_scene_graph::SceneGraph > parseURDFFile(const std::string &path, const tesseract_common::ResourceLocator &locator)
Parse a URDF file into a Tesseract Scene Graph.
Definition: urdf_parser.cpp:197
tesseract_urdf_common_unit.h
urdf_parser.h
A urdf parser for tesseract.
TESSERACT_COMMON_IGNORE_WARNINGS_POP
tesseract_urdf::writeURDFFile
void writeURDFFile(const std::shared_ptr< const tesseract_scene_graph::SceneGraph > &sg, const std::string &package_path, const std::string &urdf_name="")
Definition: urdf_parser.cpp:218
tesseract_common::GeneralResourceLocator::locateResource
std::shared_ptr< Resource > locateResource(const std::string &url) const override
tesseract_scene_graph::Joint::Ptr
std::shared_ptr< Joint > Ptr
tesseract_common::GeneralResourceLocator
macros.h
tesseract_scene_graph::SceneGraph::Ptr
std::shared_ptr< SceneGraph > Ptr
TEST
TESSERACT_COMMON_IGNORE_WARNINGS_PUSH TESSERACT_COMMON_IGNORE_WARNINGS_POP TEST(TesseractURDFUnit, parse_urdf)
Definition: tesseract_urdf_urdf_unit.cpp:14
tesseract_urdf::parseURDFString
std::unique_ptr< tesseract_scene_graph::SceneGraph > parseURDFString(const std::string &urdf_xml_string, const tesseract_common::ResourceLocator &locator)
Parse a URDF string into a Tesseract Scene Graph.
Definition: urdf_parser.cpp:53
tesseract_scene_graph
EXPECT_EQ
#define EXPECT_EQ(a, b)
EXPECT_FALSE
#define EXPECT_FALSE(args)
tesseract_scene_graph::JointType::FIXED
@ FIXED


tesseract_urdf
Author(s): Levi Armstrong
autogenerated on Thu Apr 24 2025 03:10:44