urdf_test_case.py
Go to the documentation of this file.
1 import subprocess
2 
3 from urdf_parser_py.urdf import URDF
4 from unittest import TestCase
5 
6 PKG = 'franka_description'
7 
8 class UrdfTestCase(TestCase):
9  def xacro(self, file, args=''):
10  """
11  Generates a URDF from a XACRO file. If the URDF is invalid the test is
12  automatically failed.
13  @param file: The name of the xacro input file within `franka_description/robots/`
14  @param args: A optional string of xacro args to append, e.g. ("foo:=1 bar:=true")
15  @return: The generated URDF, as urdf_parser_py.urdf.URDF type
16  """
17  try:
18  return URDF.from_xml_string(subprocess.check_output(
19  'xacro $(rospack find %s)/robots/%s %s' % (PKG, file, args),
20  shell=True)
21  )
22  except subprocess.CalledProcessError as e:
23  self.fail('Could not generate URDF from "%s", probably syntax error: %s' % (file, e.output))
24 
25  def assertContainsLink(self, urdf, link):
26  """
27  Check that the URDF contains a certain link
28  @param urdf: The URDF to test
29  @param link: The name of the link to find
30  @return: True if 'link' is present in 'urdf', False otherwise
31  """
32  self.assertIn(link, urdf.link_map, 'Link "%s" not found in URDF' % link)
33 
34  def assertContainsJoint(self, urdf, joint):
35  """
36  Check that the URDF contains a certain joint
37  @param urdf: The URDF to test
38  @param joint: The name of the joint to find
39  @return: True if 'joint' is present in 'urdf', False otherwise
40  """
41  self.assertIn(joint, urdf.joint_map, 'Joint "%s" not found in URDF' % joint)
42 
43  def links_with(self, urdf, predicate):
44  """
45  Iterate all links in the URDF and filter with a predicate
46  @param urdf: The URDF with the links to filter
47  @param predicate: A function, which gets the link name as argument and which
48  should return true if the link should be in the list or not
49  @return: A list of link names matching the predicate
50  """
51  return list(filter(predicate, urdf.link_map.keys()))
52 
53  def joints_with(self, urdf, predicate):
54  """
55  Iterate all joints in the URDF and filter with a predicate
56  @param urdf: The URDF with the joints to filter
57  @param predicate: A function, which gets the joint name as argument and which
58  should return true if the joint should be in the list or not
59  @return: A list of joint names matching the predicate
60  """
61  return list(filter(predicate, urdf.joint_map.keys()))
62 
63  def collision_geometries(self, urdf, link):
64  """
65  Find all <collision> geometries of a certain link in a URDF.
66  Fail the test if the link does not exist.
67  @param urdf: The URDF to search for
68  @param link: The name of the link to get its collision geometries for
69  @return: A list of urdf_parser_py.urdf.Geometry
70  """
71  self.assertContainsLink(urdf, link)
72  return [ collision.geometry for collision in urdf.link_map[link].collisions ]
73 
74  def assertJointBetween(self, urdf, parent, child, type=None):
75  """
76  Assert that there exists a <joint> between two links
77  @param urdf: The URDF in which to look for such a joint
78  @param parent: The name of the parent link of the joint to look for
79  @param child: The name of the child link of the joint to look for
80  @param type: None, to search for any joint, or one of ['unknown', 'revolute',
81  'continuous', 'prismatic', 'floating', 'planar', 'fixed'] to check
82  for a specific type only.
83  """
84  candidates = list(filter(lambda j: j.parent == parent, urdf.joints))
85  self.assertTrue(candidates, "Could not find any joint in URDF which parent is '%s'" % parent)
86 
87  candidates = list(filter(lambda j: j.child == child, candidates))
88  self.assertTrue(candidates, "Could not find any joint in URDF which child is '%s'" % child)
89 
90  if type is not None:
91  candidates = list(filter(lambda j: j.joint_type == type, candidates))
92  self.assertTrue(candidates, "Could not find any joint in URDF from %s -> %s which is %s" % (parent, child, type))
93 
94  def assertJointHasTransmission(self, urdf, joint, type):
95  """
96  Assert that there exists a <transmission> to a joint with a certain type
97  @param urdf: The URDF in which to look for the transmission
98  @param joint: The name of the joint for which the transmission is for
99  @param type: The type of the hw interface, e.g. 'hardware_interface/PositionJointInterface'
100  """
101  self.assertContainsJoint(urdf, joint)
102  for transmission in urdf.transmissions:
103  j = transmission.joints[0]
104  if j.name == joint and j.hardwareInterfaces[0] == type:
105  # Successfully found matching transmission, break out of loop
106  break
107  else:
108  # Transmission Loop not broken -> no suitable transmission for joint found
109  self.fail('No suitable "%s" transmission tag for "%s" found in URDF' % (type, joint))
test.urdf_test_case.UrdfTestCase.collision_geometries
def collision_geometries(self, urdf, link)
Definition: urdf_test_case.py:63
test.urdf_test_case.UrdfTestCase.assertContainsJoint
def assertContainsJoint(self, urdf, joint)
Definition: urdf_test_case.py:34
test.urdf_test_case.UrdfTestCase.joints_with
def joints_with(self, urdf, predicate)
Definition: urdf_test_case.py:53
test.urdf_test_case.UrdfTestCase.assertJointHasTransmission
def assertJointHasTransmission(self, urdf, joint, type)
Definition: urdf_test_case.py:94
test.urdf_test_case.UrdfTestCase.assertContainsLink
def assertContainsLink(self, urdf, link)
Definition: urdf_test_case.py:25
test.urdf_test_case.UrdfTestCase.xacro
def xacro(self, file, args='')
Definition: urdf_test_case.py:9
test.urdf_test_case.UrdfTestCase
Definition: urdf_test_case.py:8
test.urdf_test_case.UrdfTestCase.assertJointBetween
def assertJointBetween(self, urdf, parent, child, type=None)
Definition: urdf_test_case.py:74
test.urdf_test_case.UrdfTestCase.links_with
def links_with(self, urdf, predicate)
Definition: urdf_test_case.py:43


franka_description
Author(s): Franka Emika GmbH
autogenerated on Mon Sep 19 2022 02:33:19