Skip to content

Commit

Permalink
Add tests for mutli-visual and multi-collision
Browse files Browse the repository at this point in the history
  • Loading branch information
sloretz authored and clalancette committed Feb 15, 2018
1 parent 5486300 commit 4a4451f
Showing 1 changed file with 38 additions and 0 deletions.
38 changes: 38 additions & 0 deletions test/test_urdf.py
Original file line number Diff line number Diff line change
Expand Up @@ -144,6 +144,44 @@ def test_robot_material_missing_color_and_texture(self):
</robot>'''
self.assertRaises(ParseException, self.parse, xml)

def test_link_multiple_visual(self):
xml = '''<?xml version="1.0"?>
<robot name="test">
<link name="link">
<visual>
<geometry>
<cylinder length="1" radius="1"/>
</geometry>
<material name="mat"/>
</visual>
<visual>
<geometry>
<cylinder length="4" radius="0.5"/>
</geometry>
<material name="mat2"/>
</visual>
</link>
</robot>'''
self.parse_and_compare(xml)

def test_link_multiple_collision(self):
xml = '''<?xml version="1.0"?>
<robot name="test">
<link name="link">
<collision>
<geometry>
<cylinder length="1" radius="1"/>
</geometry>
</collision>
<collision>
<geometry>
<cylinder length="4" radius="0.5"/>
</geometry>
</collision>
</link>
</robot>'''
self.parse_and_compare(xml)


class LinkOriginTestCase(unittest.TestCase):
@mock.patch('urdf_parser_py.xml_reflection.on_error',
Expand Down

0 comments on commit 4a4451f

Please sign in to comment.