3 #include <gtest/gtest.h>
4 #include <Eigen/Geometry>
14 TEST(TesseractURDFUnit, parse_urdf)
19 R
"(<robot name="test" extra="0 0 0" tesseract:make_convex="true">
20 <joint name="j1" type="fixed">
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"/>
44 R
"(<robot name="test" extra="0 0 0" tesseract:make_convex="true">
45 <joint name="j1" type="fixed">
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"/>
69 R
"(<robot name="test" tesseract:make_convex="true">
70 <joint name="j1" type="fixed">
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"/>
80 <joint name="j2" type="fixed">
92 R
"(<robot name="test" tesseract:make_convex="true">
93 <joint name="j1" type="fixed">
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"/>
103 <joint name="j2" type="fixed">
115 R
"(<robot name="test" tesseract:make_convex="true">
116 <joint name="j1" type="fixed">
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"/>
134 R
"(<robot name="test" tesseract:make_convex="true">
135 <joint name="j1" type="fixed">
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"/>
154 R
"(<robot name="test" tesseract:make_convex="true">
155 <joint name="j1" type="fixed">
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"/>
173 R
"(<robot name="test" tesseract:make_convex="true">
174 <joint name="j1" type="fixed">
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"/>
193 R
"(<robot tesseract:make_convex="true">
194 <joint name="j1" type="fixed" >
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"/>
212 R
"(<robot name="test" tesseract:make_convex="true">
213 <joint name="j1" type="fixed">
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"/>
223 <joint name="j1" type="fixed">
236 std::string str = R
"(this is not a urdf)";
242 std::string str = R
"(<abcd name="test"></abcd>)";
248 std::string str = R
"(<robot name="test" tesseract:make_convex="true" version="a"></robot>)";
254 std::string str = R
"(<robot name="test" tesseract:make_convex="true" version="2"></robot>)";
260 std::string str = R
"(<robot name="test"></robot>)";
266 std::string str = R
"(<robot name="test" tesseract:make_convex="1.5"></robot>)";
271 const std::string path =
272 resource_locator.
locateResource(
"package://tesseract_support/urdf/lbr_iiwa_14_r820.urdf")->getFilePath();
278 TEST(TesseractURDFUnit, parse_urdf_with_available_materials)
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"/>
287 <joint name="j1" type="fixed">
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"/>
299 <origin xyz="0 0 0" rpy="0 0 0" />
303 <material name="test_material"/>
315 EXPECT_EQ(sg->getLink(
"l1")->visual[0]->material->getName(),
"test_material");
320 R
"(<robot name="test" extra="0 0 0" tesseract:make_convex="true">
321 <joint name="j1" type="fixed">
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"/>
333 <origin xyz="0 0 0" rpy="0 0 0" />
337 <material name="test_material" extra="0 0 0">
338 <color rgba="1 .5 .5 1" extra="0 0 0"/>
344 <origin xyz="0 0 0" rpy="0 0 0" />
348 <material name="test_material" />
359 EXPECT_EQ(sg->getLink(
"l1")->visual[0]->material->getName(),
"test_material");
364 R
"(<robot name="test" extra="0 0 0" tesseract:make_convex="true">
365 <joint name="j1" type="fixed">
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"/>
377 <origin xyz="0 0 0" rpy="0 0 0" />
381 <material name="test_material" />
386 <origin xyz="0 0 0" rpy="0 0 0" />
390 <material name="test_material" extra="0 0 0">
391 <color rgba="1 .5 .5 1" extra="0 0 0"/>
401 R
"(<robot name="test" extra="0 0 0" tesseract:make_convex="true">
402 <joint name="j1" type="fixed">
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"/>
414 <origin xyz="0 0 0" rpy="0 0 0" />
418 <material name="test_material" extra="0 0 0">
419 <color rgba="1 .5 .5 1" extra="0 0 0"/>
425 <origin xyz="0 0 0" rpy="0 0 0" />
429 <material name="test_material" extra="0 0 0">
430 <color rgba="1 .5 .5 1" extra="0 0 0"/>
440 TEST(TesseractURDFUnit, LoadURDFUnit)
445 std::string urdf_file =
446 locator.
locateResource(
"package://tesseract_support/urdf/lbr_iiwa_14_r820.urdf")->getFilePath();
459 auto path = g->getShortestPath(
"link_1",
"link_4");
461 std::cout << path <<
"\n";
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());
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());
473 TEST(TesseractURDFUnit, write_urdf)
496 sg->addLink(*link_0);
497 sg->addLink(*link_1);
502 joint_0->parent_link_name = link_0->getName();
503 joint_0->child_link_name = link_1->getName();
504 sg->addJoint(*joint_0);