test_urdf.py
Go to the documentation of this file.
1 
2 import unittest
3 import mock
4 import os
5 import sys
6 
7 # Add path to import xml_matching
8 sys.path.append(os.path.abspath(os.path.join(os.path.dirname(__file__), '.')))
9 sys.path.append(os.path.abspath(os.path.join(os.path.dirname(__file__),
10  '../src')))
11 
12 from xml.dom import minidom # noqa
13 from xml_matching import xml_matches # noqa
14 from urdf_parser_py import urdf # noqa
15 import urdf_parser_py.xml_reflection as xmlr
16 
17 class ParseException(xmlr.core.ParseError):
18  def __init__(self, e = "", path = ""):
19  super(ParseException, self).__init__(e, path)
20 
21 
22 class TestURDFParser(unittest.TestCase):
23  @mock.patch('urdf_parser_py.xml_reflection.on_error',
24  mock.Mock(side_effect=ParseException))
25  def parse(self, xml):
26  return urdf.Robot.from_xml_string(xml)
27 
28  def parse_and_compare(self, orig):
29  xml = minidom.parseString(orig)
30  robot = urdf.Robot.from_xml_string(orig)
31  rewritten = minidom.parseString(robot.to_xml_string())
32  self.assertTrue(xml_matches(xml, rewritten))
33 
34  def xml_and_compare(self, robot, xml):
35  robot_xml_string = robot.to_xml_string()
36  robot_xml = minidom.parseString(robot_xml_string)
37  orig_xml = minidom.parseString(xml)
38  self.assertTrue(xml_matches(robot_xml, orig_xml))
39 
41  xml = '''<?xml version="1.0"?>
42 <robot name="test" version="1.0">
43  <transmission name="simple_trans">
44  <type>transmission_interface/SimpleTransmission</type>
45  <joint name="foo_joint">
46  <hardwareInterface>EffortJointInterface</hardwareInterface>
47  </joint>
48  <actuator name="foo_motor">
49  <mechanicalReduction>50.0</mechanicalReduction>
50  </actuator>
51  </transmission>
52 </robot>'''
53  self.parse_and_compare(xml)
54 
55  robot = urdf.Robot(name='test', version='1.0')
56  trans = urdf.Transmission(name='simple_trans')
57  trans.type = 'transmission_interface/SimpleTransmission'
58  joint = urdf.TransmissionJoint(name='foo_joint')
59  joint.add_aggregate('hardwareInterface', 'EffortJointInterface')
60  trans.add_aggregate('joint', joint)
61  actuator = urdf.Actuator(name='foo_motor')
62  actuator.mechanicalReduction = 50.0
63  trans.add_aggregate('actuator', actuator)
64  robot.add_aggregate('transmission', trans)
65  self.xml_and_compare(robot, xml)
66 
68  xml = '''<?xml version="1.0"?>
69 <robot name="test" version="1.0">
70  <transmission name="simple_trans">
71  <type>transmission_interface/SimpleTransmission</type>
72  <joint name="foo_joint">
73  <hardwareInterface>EffortJointInterface</hardwareInterface>
74  </joint>
75  <joint name="bar_joint">
76  <hardwareInterface>EffortJointInterface</hardwareInterface>
77  <hardwareInterface>EffortJointInterface</hardwareInterface>
78  </joint>
79  <actuator name="foo_motor">
80  <mechanicalReduction>50.0</mechanicalReduction>
81  </actuator>
82  </transmission>
83 </robot>'''
84  self.parse_and_compare(xml)
85 
86  robot = urdf.Robot(name='test', version='1.0')
87  trans = urdf.Transmission(name='simple_trans')
88  trans.type = 'transmission_interface/SimpleTransmission'
89  joint = urdf.TransmissionJoint(name='foo_joint')
90  joint.add_aggregate('hardwareInterface', 'EffortJointInterface')
91  trans.add_aggregate('joint', joint)
92  joint = urdf.TransmissionJoint(name='bar_joint')
93  joint.add_aggregate('hardwareInterface', 'EffortJointInterface')
94  joint.add_aggregate('hardwareInterface', 'EffortJointInterface')
95  trans.add_aggregate('joint', joint)
96  actuator = urdf.Actuator(name='foo_motor')
97  actuator.mechanicalReduction = 50.0
98  trans.add_aggregate('actuator', actuator)
99  robot.add_aggregate('transmission', trans)
100  self.xml_and_compare(robot, xml)
101 
103  xml = '''<?xml version="1.0"?>
104 <robot name="test" version="1.0">
105  <transmission name="simple_trans">
106  <type>transmission_interface/SimpleTransmission</type>
107  <joint name="foo_joint">
108  <hardwareInterface>EffortJointInterface</hardwareInterface>
109  </joint>
110  <actuator name="foo_motor">
111  <mechanicalReduction>50.0</mechanicalReduction>
112  </actuator>
113  <actuator name="bar_motor"/>
114  </transmission>
115 </robot>'''
116  self.parse_and_compare(xml)
117 
118  robot = urdf.Robot(name='test', version='1.0')
119  trans = urdf.Transmission(name='simple_trans')
120  trans.type = 'transmission_interface/SimpleTransmission'
121  joint = urdf.TransmissionJoint(name='foo_joint')
122  joint.add_aggregate('hardwareInterface', 'EffortJointInterface')
123  trans.add_aggregate('joint', joint)
124  actuator = urdf.Actuator(name='foo_motor')
125  actuator.mechanicalReduction = 50.0
126  trans.add_aggregate('actuator', actuator)
127  actuator = urdf.Actuator(name='bar_motor')
128  trans.add_aggregate('actuator', actuator)
129  robot.add_aggregate('transmission', trans)
130  self.xml_and_compare(robot, xml)
131 
133  xml = '''<?xml version="1.0"?>
134 <robot name="test" version="1.0">
135  <transmission name="simple_trans">
136  <type>transmission_interface/SimpleTransmission</type>
137  </transmission>
138 </robot>'''
139  self.assertRaises(xmlr.core.ParseError, self.parse, xml)
140 
142  xml = '''<?xml version="1.0"?>
143 <robot name="test" version="1.0">
144  <transmission name="simple_trans">
145  <type>transmission_interface/SimpleTransmission</type>
146  <joint name="foo_joint">
147  <hardwareInterface>EffortJointInterface</hardwareInterface>
148  </joint>
149  </transmission>
150 </robot>'''
151  self.assertRaises(xmlr.core.ParseError, self.parse, xml)
152 
154  xml = '''<?xml version="1.0"?>
155 <robot name="test" version="1.0">
156  <transmission name="PR2_trans" type="SimpleTransmission">
157  <joint name="foo_joint"/>
158  <actuator name="foo_motor"/>
159  <mechanicalReduction>1.0</mechanicalReduction>
160  </transmission>
161 </robot>'''
162  self.parse_and_compare(xml)
163 
164  robot = urdf.Robot(name='test', version='1.0')
165  trans = urdf.PR2Transmission(name='PR2_trans', joint='foo_joint', actuator='foo_motor', type='SimpleTransmission', mechanicalReduction=1.0)
166  robot.add_aggregate('transmission', trans)
167  self.xml_and_compare(robot, xml)
168 
170  xml = '''<?xml version="1.0"?>
171 <robot name="test" version="1.0">
172  <link name="link">
173  <visual>
174  <geometry>
175  <cylinder length="1" radius="1"/>
176  </geometry>
177  <material name="mat"/>
178  </visual>
179  </link>
180 </robot>'''
181  self.parse_and_compare(xml)
182 
183  robot = urdf.Robot(name='test', version='1.0')
184  link = urdf.Link(name='link',
185  visual=urdf.Visual(geometry=urdf.Cylinder(length=1, radius=1),
186  material=urdf.Material(name='mat')))
187  robot.add_link(link)
188  self.xml_and_compare(robot, xml)
189 
190  robot = urdf.Robot(name='test', version='1.0')
191  link = urdf.Link(name='link')
192  link.visual = urdf.Visual(geometry=urdf.Cylinder(length=1, radius=1),
193  material=urdf.Material(name='mat'))
194  robot.add_link(link)
195  self.xml_and_compare(robot, xml)
196 
198  xml = '''<?xml version="1.0"?>
199 <robot name="test" version="1.0">
200  <material name="mat">
201  <color rgba="0.0 0.0 0.0 1.0"/>
202  </material>
203 </robot>'''
204  self.parse_and_compare(xml)
205 
206  robot = urdf.Robot(name='test', version='1.0')
207  material = urdf.Material(name='mat', color=urdf.Color([0.0, 0.0, 0.0, 1.0]))
208  robot.add_aggregate('material', material)
209  self.xml_and_compare(robot, xml)
210 
212  xml = '''<?xml version="1.0"?>
213 <robot name="test" version="1.0">
214  <material name="mat"/>
215 </robot>'''
216  self.assertRaises(xmlr.core.ParseError, self.parse, xml)
217 
219  xml = '''<?xml version="1.0"?>
220 <robot name="test" version="1.0">
221  <link name="link">
222  <visual>
223  <geometry>
224  <cylinder length="1" radius="1"/>
225  </geometry>
226  <material name="mat"/>
227  </visual>
228  <visual>
229  <geometry>
230  <cylinder length="4" radius="0.5"/>
231  </geometry>
232  <material name="mat2"/>
233  </visual>
234  </link>
235 </robot>'''
236  self.parse_and_compare(xml)
237 
238  robot = urdf.Robot(name='test', version='1.0')
239  link = urdf.Link(name='link')
240  link.visual = urdf.Visual(geometry=urdf.Cylinder(length=1, radius=1),
241  material=urdf.Material(name='mat'))
242  link.visual = urdf.Visual(geometry=urdf.Cylinder(length=4, radius=0.5),
243  material=urdf.Material(name='mat2'))
244  robot.add_link(link)
245  self.xml_and_compare(robot, xml)
246 
248  xml = '''<?xml version="1.0"?>
249 <robot name="test" version="1.0">
250  <link name="link">
251  <visual name="alice">
252  <geometry>
253  <cylinder length="1" radius="1"/>
254  </geometry>
255  <material name="mat"/>
256  </visual>
257  </link>
258 </robot>'''
259  self.parse_and_compare(xml)
260 
262  xml = '''<?xml version="1.0"?>
263 <robot name="test" version="1.0">
264  <link name="link">
265  <collision>
266  <geometry>
267  <cylinder length="1" radius="1"/>
268  </geometry>
269  </collision>
270  <collision>
271  <geometry>
272  <cylinder length="4" radius="0.5"/>
273  </geometry>
274  </collision>
275  </link>
276 </robot>'''
277  self.parse_and_compare(xml)
278 
279  robot = urdf.Robot(name='test', version='1.0')
280  link = urdf.Link(name='link')
281  link.collision = urdf.Collision(geometry=urdf.Cylinder(length=1, radius=1))
282  link.collision = urdf.Collision(geometry=urdf.Cylinder(length=4, radius=0.5))
283  robot.add_link(link)
284  self.xml_and_compare(robot, xml)
285 
287  xml = '''<?xml version="1.0"?>
288 <robot name="test" version="1.0">
289  <link name="link">
290  <collision name="alice">
291  <geometry>
292  <cylinder length="1" radius="1"/>
293  </geometry>
294  </collision>
295  </link>
296 </robot>'''
297  self.parse_and_compare(xml)
298 
300  xml = '''<?xml version="1.0"?>
301 <robot name="test" version="1">
302 </robot>'''
303  self.assertRaises(ValueError, self.parse, xml)
304 
306  xml = '''<?xml version="1.0"?>
307 <robot name="test" version="1.0.0">
308 </robot>'''
309  self.assertRaises(ValueError, self.parse, xml)
310 
312  xml = '''<?xml version="1.0"?>
313 <robot name="test" version="1.">
314 </robot>'''
315  self.assertRaises(ValueError, self.parse, xml)
316 
318  xml = '''<?xml version="1.0"?>
319 <robot name="test" version=".0">
320 </robot>'''
321  self.assertRaises(ValueError, self.parse, xml)
322 
324  xml = '''<?xml version="1.0"?>
325 <robot name="test" version="-1.0">
326 </robot>'''
327  self.assertRaises(ValueError, self.parse, xml)
328 
330  xml = '''<?xml version="1.0"?>
331 <robot name="test" version="1.-0">
332 </robot>'''
333  self.assertRaises(ValueError, self.parse, xml)
334 
336  xml = '''<?xml version="1.0"?>
337 <robot name="test" version="a.c">
338 </robot>'''
339  self.assertRaises(ValueError, self.parse, xml)
340 
342  xml = '''<?xml version="1.0"?>
343 <robot name="test" version="1.c">
344 </robot>'''
345  self.assertRaises(ValueError, self.parse, xml)
346 
348  xml = '''<?xml version="1.0"?>
349 <robot name="test" version="1.0~pre6">
350 </robot>'''
351  self.assertRaises(ValueError, self.parse, xml)
352 
354  xml = '''<?xml version="1.0"?>
355 <robot name="test" version="1.0">
356 </robot>'''
357  self.parse_and_compare(xml)
358 
360  xml = '''<?xml version="1.0"?>
361 <robot name="test" version="foo">
362 </robot>'''
363  self.assertRaises(ValueError, self.parse, xml)
364 
366  xml = '''<?xml version="1.0"?>
367 <robot name="test" version="2.0">
368 </robot>'''
369  self.assertRaises(ValueError, self.parse, xml)
370 
371 class LinkOriginTestCase(unittest.TestCase):
372  @mock.patch('urdf_parser_py.xml_reflection.on_error',
373  mock.Mock(side_effect=ParseException))
374  def parse(self, xml):
375  return urdf.Robot.from_xml_string(xml)
376 
378  xml = '''<?xml version="1.0"?>
379 <robot name="test">
380  <link name="test_link">
381  <inertial>
382  <mass value="10.0"/>
383  <origin/>
384  </inertial>
385  </link>
386 </robot>'''
387  robot = self.parse(xml)
388  origin = robot.links[0].inertial.origin
389  self.assertEqual(origin.xyz, [0, 0, 0])
390  self.assertEqual(origin.rpy, [0, 0, 0])
391 
393  xml = '''<?xml version="1.0"?>
394 <robot name="test">
395  <link name="test_link">
396  <inertial>
397  <mass value="10.0"/>
398  <origin xyz="1 2 3"/>
399  </inertial>
400  </link>
401 </robot>'''
402  robot = self.parse(xml)
403  origin = robot.links[0].inertial.origin
404  self.assertEqual(origin.xyz, [1, 2, 3])
405  self.assertEqual(origin.rpy, [0, 0, 0])
406 
407 
408 class LinkMultiVisualsAndCollisionsTest(unittest.TestCase):
409 
410  xml = '''<?xml version="1.0"?>
411 <robot name="test" version="1.0">
412  <link name="link">
413  <visual>
414  <geometry>
415  <cylinder length="1" radius="1"/>
416  </geometry>
417  <material name="mat"/>
418  </visual>
419  <visual>
420  <geometry>
421  <cylinder length="4" radius="0.5"/>
422  </geometry>
423  <material name="mat2"/>
424  </visual>
425  <collision>
426  <geometry>
427  <cylinder length="1" radius="1"/>
428  </geometry>
429  </collision>
430  <collision>
431  <geometry>
432  <cylinder length="4" radius="0.5"/>
433  </geometry>
434  </collision>
435  </link>
436  <link name="link2"/>
437 </robot>'''
438 
440  robot = urdf.Robot.from_xml_string(self.xml)
441  self.assertEqual(2, len(robot.links[0].visuals))
442  self.assertEqual(
443  id(robot.links[0].visuals[0]), id(robot.links[0].visual))
444 
445  self.assertEqual(None, robot.links[1].visual)
446 
447  dummyObject = set()
448  robot.links[0].visual = dummyObject
449  self.assertEqual(id(dummyObject), id(robot.links[0].visuals[0]))
450 
452  robot = urdf.Robot.from_xml_string(self.xml)
453  self.assertEqual(2, len(robot.links[0].collisions))
454  self.assertEqual(
455  id(robot.links[0].collisions[0]), id(robot.links[0].collision))
456 
457  self.assertEqual(None, robot.links[1].collision)
458 
459  dummyObject = set()
460  robot.links[0].collision = dummyObject
461  self.assertEqual(id(dummyObject), id(robot.links[0].collisions[0]))
462 
464  robot = urdf.Robot(name='test', version='1.0')
465  link = urdf.Link(name='link')
466  link.visual = urdf.Visual(geometry=urdf.Cylinder(length=1, radius=1),
467  material=urdf.Material(name='mat'))
468  link.visual = urdf.Visual(geometry=urdf.Cylinder(length=4, radius=0.5),
469  material=urdf.Material(name='mat2'))
470  link.collision = urdf.Collision(geometry=urdf.Cylinder(length=1, radius=1))
471  link.collision = urdf.Collision(geometry=urdf.Cylinder(length=4, radius=0.5))
472  robot.add_link(link)
473  link = urdf.Link(name='link2')
474  robot.add_link(link)
475  #
476  robot_xml_string = robot.to_xml_string()
477  robot_xml = minidom.parseString(robot_xml_string)
478  orig_xml = minidom.parseString(self.xml)
479  self.assertTrue(xml_matches(robot_xml, orig_xml))
480 
482  robot = urdf.Robot(name='test', version='1.0')
483  link = urdf.Link(name='link')
484  link.add_aggregate('visual', urdf.Visual(geometry=urdf.Cylinder(length=1, radius=1),
485  material=urdf.Material(name='mat')))
486  link.add_aggregate('visual', urdf.Visual(geometry=urdf.Cylinder(length=4, radius=0.5),
487  material=urdf.Material(name='mat2')))
488  link.add_aggregate('collision', urdf.Collision(geometry=urdf.Cylinder(length=1, radius=1)))
489  link.add_aggregate('collision', urdf.Collision(geometry=urdf.Cylinder(length=4, radius=0.5)))
490  robot.add_link(link)
491  link = urdf.Link(name='link2')
492  robot.add_link(link)
493  #
494  robot_xml_string = robot.to_xml_string()
495  robot_xml = minidom.parseString(robot_xml_string)
496  orig_xml = minidom.parseString(self.xml)
497  self.assertTrue(xml_matches(robot_xml, orig_xml))
498 
499 class TestCreateNew(unittest.TestCase):
500  def test_new_urdf(self):
501  testcase = urdf.URDF('robot_name').to_xml()
502  self.assertTrue('name' in testcase.keys())
503  self.assertTrue('version' in testcase.keys())
504  self.assertEqual(testcase.get('name'), 'robot_name')
505  self.assertEqual(testcase.get('version'), '1.0')
506 
508  testcase = urdf.URDF('robot_name', '1.0').to_xml()
509  self.assertTrue('name' in testcase.keys())
510  self.assertTrue('version' in testcase.keys())
511  self.assertEqual(testcase.get('name'), 'robot_name')
512  self.assertEqual(testcase.get('version'), '1.0')
513 
514 
515 if __name__ == '__main__':
516  unittest.main()
test_urdf.ParseException.__init__
def __init__(self, e="", path="")
Definition: test_urdf.py:18
test_urdf.LinkMultiVisualsAndCollisionsTest
Definition: test_urdf.py:408
test_urdf.LinkMultiVisualsAndCollisionsTest.test_xml_and_urdfdom_robot_compatible_with_kinetic
def test_xml_and_urdfdom_robot_compatible_with_kinetic(self)
Definition: test_urdf.py:463
test_urdf.TestCreateNew.test_new_urdf
def test_new_urdf(self)
Definition: test_urdf.py:500
test_urdf.TestURDFParser.test_version_attribute_invalid_version
def test_version_attribute_invalid_version(self)
Definition: test_urdf.py:365
test_urdf.TestURDFParser.parse_and_compare
def parse_and_compare(self, orig)
Definition: test_urdf.py:28
test_urdf.TestCreateNew
Definition: test_urdf.py:499
test_urdf.LinkOriginTestCase.test_robot_link_defaults
def test_robot_link_defaults(self)
Definition: test_urdf.py:377
test_urdf.TestURDFParser.test_robot_material
def test_robot_material(self)
Definition: test_urdf.py:197
test_urdf.TestURDFParser.xml_and_compare
def xml_and_compare(self, robot, xml)
Definition: test_urdf.py:34
test_urdf.TestURDFParser.test_version_attribute_negative_major_number
def test_version_attribute_negative_major_number(self)
Definition: test_urdf.py:323
test_urdf.LinkMultiVisualsAndCollisionsTest.test_multi_visual_access
def test_multi_visual_access(self)
Definition: test_urdf.py:439
test_urdf.TestURDFParser.test_version_attribute_dots_one_number
def test_version_attribute_dots_one_number(self)
Definition: test_urdf.py:341
test_urdf.TestURDFParser.test_version_attribute_negative_minor_number
def test_version_attribute_negative_minor_number(self)
Definition: test_urdf.py:329
test_urdf.TestURDFParser.test_old_transmission
def test_old_transmission(self)
Definition: test_urdf.py:153
test_urdf.TestURDFParser.test_new_transmission_multiple_actuators
def test_new_transmission_multiple_actuators(self)
Definition: test_urdf.py:102
test_urdf.ParseException
Definition: test_urdf.py:17
test_urdf.LinkOriginTestCase.test_robot_link_defaults_xyz_set
def test_robot_link_defaults_xyz_set(self)
Definition: test_urdf.py:392
test_urdf.TestURDFParser.parse
def parse(self, xml)
Definition: test_urdf.py:25
test_urdf.TestURDFParser.test_version_attribute_correct
def test_version_attribute_correct(self)
Definition: test_urdf.py:353
test_urdf.TestURDFParser.test_link_multiple_collision
def test_link_multiple_collision(self)
Definition: test_urdf.py:261
test_urdf.TestURDFParser.test_new_transmission_multiple_joints
def test_new_transmission_multiple_joints(self)
Definition: test_urdf.py:67
xml_matching.xml_matches
def xml_matches(a, b, ignore_nodes=[])
Definition: xml_matching.py:96
urdf_parser_py.xml_reflection
Definition: xml_reflection/__init__.py:1
test_urdf.TestURDFParser.test_robot_material_missing_color_and_texture
def test_robot_material_missing_color_and_texture(self)
Definition: test_urdf.py:211
test_urdf.TestURDFParser.test_collision_with_name
def test_collision_with_name(self)
Definition: test_urdf.py:286
test_urdf.LinkMultiVisualsAndCollisionsTest.test_xml_and_urdfdom_robot_only_supported_since_melodic
def test_xml_and_urdfdom_robot_only_supported_since_melodic(self)
Definition: test_urdf.py:481
test_urdf.TestURDFParser.test_version_attribute_trailing_junk
def test_version_attribute_trailing_junk(self)
Definition: test_urdf.py:347
test_urdf.TestURDFParser.test_new_transmission_missing_actuator
def test_new_transmission_missing_actuator(self)
Definition: test_urdf.py:141
test_urdf.TestURDFParser.test_version_attribute_no_major_number
def test_version_attribute_no_major_number(self)
Definition: test_urdf.py:317
test_urdf.LinkOriginTestCase.parse
def parse(self, xml)
Definition: test_urdf.py:374
test_urdf.TestURDFParser.test_version_attribute_not_enough_numbers
def test_version_attribute_not_enough_numbers(self)
Definition: test_urdf.py:311
test_urdf.TestURDFParser.test_link_material_missing_color_and_texture
def test_link_material_missing_color_and_texture(self)
Definition: test_urdf.py:169
test_urdf.LinkMultiVisualsAndCollisionsTest.test_multi_collision_access
def test_multi_collision_access(self)
Definition: test_urdf.py:451
test_urdf.TestCreateNew.test_new_urdf_with_version
def test_new_urdf_with_version(self)
Definition: test_urdf.py:507
test_urdf.TestURDFParser.test_version_attribute_dots_no_numbers
def test_version_attribute_dots_no_numbers(self)
Definition: test_urdf.py:335
test_urdf.TestURDFParser.test_link_multiple_visual
def test_link_multiple_visual(self)
Definition: test_urdf.py:218
test_urdf.LinkOriginTestCase
Definition: test_urdf.py:371
test_urdf.TestURDFParser.test_new_transmission
def test_new_transmission(self)
Definition: test_urdf.py:40
test_urdf.TestURDFParser.test_version_attribute_too_many_dots
def test_version_attribute_too_many_dots(self)
Definition: test_urdf.py:305
test_urdf.LinkMultiVisualsAndCollisionsTest.xml
xml
Definition: test_urdf.py:410
test_urdf.TestURDFParser.test_version_attribute_invalid
def test_version_attribute_invalid(self)
Definition: test_urdf.py:359
test_urdf.TestURDFParser.test_version_attribute_not_enough_dots
def test_version_attribute_not_enough_dots(self)
Definition: test_urdf.py:299
test_urdf.TestURDFParser.test_new_transmission_missing_joint
def test_new_transmission_missing_joint(self)
Definition: test_urdf.py:132
test_urdf.TestURDFParser.test_visual_with_name
def test_visual_with_name(self)
Definition: test_urdf.py:247
test_urdf.TestURDFParser
Definition: test_urdf.py:22


urdfdom_py
Author(s): Thomas Moulard, David Lu, Kelsey Hawkins, Antonio El Khoury, Eric Cousineau, Ioan Sucan , Jackie Kay
autogenerated on Wed Mar 2 2022 01:08:39