3 from urdf_parser_py.urdf
import URDF
4 from unittest
import TestCase
6 PKG =
'franka_description'
9 def xacro(self, file, args=''):
11 Generates a URDF from a XACRO file. If the URDF is invalid the test is
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
18 return URDF.from_xml_string(subprocess.check_output(
19 'xacro $(rospack find %s)/robots/%s %s' % (PKG, file, args),
22 except subprocess.CalledProcessError
as e:
23 self.fail(
'Could not generate URDF from "%s", probably syntax error: %s' % (file, e.output))
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
32 self.assertIn(link, urdf.link_map,
'Link "%s" not found in URDF' % link)
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
41 self.assertIn(joint, urdf.joint_map,
'Joint "%s" not found in URDF' % joint)
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
51 return list(filter(predicate, urdf.link_map.keys()))
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
61 return list(filter(predicate, urdf.joint_map.keys()))
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
72 return [ collision.geometry
for collision
in urdf.link_map[link].collisions ]
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.
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)
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)
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))
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'
102 for transmission
in urdf.transmissions:
103 j = transmission.joints[0]
104 if j.name == joint
and j.hardwareInterfaces[0] == type:
109 self.fail(
'No suitable "%s" transmission tag for "%s" found in URDF' % (type, joint))