Skip to content

Commit

Permalink
Add Link.visual and Link.collision properties (#28)
Browse files Browse the repository at this point in the history
Properties are for backwards compatibility. They access the first
element of Link.visuals and Link.collisions
  • Loading branch information
sloretz authored Feb 16, 2018
1 parent 4a4451f commit 44d82bd
Show file tree
Hide file tree
Showing 2 changed files with 85 additions and 0 deletions.
29 changes: 29 additions & 0 deletions src/urdf_parser_py/urdf.py
Original file line number Diff line number Diff line change
Expand Up @@ -359,6 +359,35 @@ def __init__(self, name=None, visual=None, inertial=None, collision=None,
self.collisions = []
self.origin = origin

def __get_visual(self):
"""Return the first visual or None."""
if self.visuals:
return self.visuals[0]

def __set_visual(self, visual):
"""Set the first visual."""
if self.visuals:
self.visuals[0] = visual
else:
self.visuals.append(visual)

def __get_collision(self):
"""Return the first collision or None."""
if self.collisions:
return self.collisions[0]

def __set_collision(self, collision):
"""Set the first collision."""
if self.collisions:
self.collisions[0] = collision
else:
self.collisions.append(collision)

# Properties for backwards compatibility
visual = property(__get_visual, __set_visual)
collision = property(__get_collision, __set_collision)


xmlr.reflect(Link, tag='link', params=[
name_attribute,
origin_element,
Expand Down
56 changes: 56 additions & 0 deletions test/test_urdf.py
Original file line number Diff line number Diff line change
Expand Up @@ -220,5 +220,61 @@ def test_robot_link_defaults_xyz_set(self):
self.assertEquals(origin.rpy, [0, 0, 0])


class LinkMultiVisualsAndCollisionsTest(unittest.TestCase):

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>
<collision>
<geometry>
<cylinder length="1" radius="1"/>
</geometry>
</collision>
<collision>
<geometry>
<cylinder length="4" radius="0.5"/>
</geometry>
</collision>
</link>
<link name="link2"/>
</robot>'''

def test_multi_visual_access(self):
robot = urdf.Robot.from_xml_string(self.xml)
self.assertEquals(2, len(robot.links[0].visuals))
self.assertEqual(
id(robot.links[0].visuals[0]), id(robot.links[0].visual))

self.assertEquals(None, robot.links[1].visual)

dummyObject = set()
robot.links[0].visual = dummyObject
self.assertEquals(id(dummyObject), id(robot.links[0].visuals[0]))

def test_multi_collision_access(self):
robot = urdf.Robot.from_xml_string(self.xml)
self.assertEquals(2, len(robot.links[0].collisions))
self.assertEqual(
id(robot.links[0].collisions[0]), id(robot.links[0].collision))

self.assertEquals(None, robot.links[1].collision)

dummyObject = set()
robot.links[0].collision = dummyObject
self.assertEquals(id(dummyObject), id(robot.links[0].collisions[0]))


if __name__ == '__main__':
unittest.main()

0 comments on commit 44d82bd

Please sign in to comment.