
Public Member Functions | |
| def | assertContainsJoint (self, urdf, joint) |
| def | assertContainsLink (self, urdf, link) |
| def | assertJointBetween (self, urdf, parent, child, type=None) |
| def | assertJointHasTransmission (self, urdf, joint, type) |
| def | collision_geometries (self, urdf, link) |
| def | joints_with (self, urdf, predicate) |
| def | links_with (self, urdf, predicate) |
| def | xacro (self, file, args='') |
Definition at line 8 of file urdf_test_case.py.
| def test.urdf_test_case.UrdfTestCase.assertContainsJoint | ( | self, | |
| urdf, | |||
| joint | |||
| ) |
Check that the URDF contains a certain joint @param urdf: The URDF to test @param joint: The name of the joint to find @return: True if 'joint' is present in 'urdf', False otherwise
Definition at line 34 of file urdf_test_case.py.
| def test.urdf_test_case.UrdfTestCase.assertContainsLink | ( | self, | |
| urdf, | |||
| link | |||
| ) |
Check that the URDF contains a certain link @param urdf: The URDF to test @param link: The name of the link to find @return: True if 'link' is present in 'urdf', False otherwise
Definition at line 25 of file urdf_test_case.py.
| def test.urdf_test_case.UrdfTestCase.assertJointBetween | ( | self, | |
| urdf, | |||
| parent, | |||
| child, | |||
type = None |
|||
| ) |
Assert that there exists a <joint> between two links
@param urdf: The URDF in which to look for such a joint
@param parent: The name of the parent link of the joint to look for
@param child: The name of the child link of the joint to look for
@param type: None, to search for any joint, or one of ['unknown', 'revolute',
'continuous', 'prismatic', 'floating', 'planar', 'fixed'] to check
for a specific type only.
Definition at line 74 of file urdf_test_case.py.
| def test.urdf_test_case.UrdfTestCase.assertJointHasTransmission | ( | self, | |
| urdf, | |||
| joint, | |||
| type | |||
| ) |
Assert that there exists a <transmission> to a joint with a certain type @param urdf: The URDF in which to look for the transmission @param joint: The name of the joint for which the transmission is for @param type: The type of the hw interface, e.g. 'hardware_interface/PositionJointInterface'
Definition at line 94 of file urdf_test_case.py.
| def test.urdf_test_case.UrdfTestCase.collision_geometries | ( | self, | |
| urdf, | |||
| link | |||
| ) |
Find all <collision> geometries of a certain link in a URDF. Fail the test if the link does not exist. @param urdf: The URDF to search for @param link: The name of the link to get its collision geometries for @return: A list of urdf_parser_py.urdf.Geometry
Definition at line 63 of file urdf_test_case.py.
| def test.urdf_test_case.UrdfTestCase.joints_with | ( | self, | |
| urdf, | |||
| predicate | |||
| ) |
Iterate all joints in the URDF and filter with a predicate
@param urdf: The URDF with the joints to filter
@param predicate: A function, which gets the joint name as argument and which
should return true if the joint should be in the list or not
@return: A list of joint names matching the predicate
Definition at line 53 of file urdf_test_case.py.
| def test.urdf_test_case.UrdfTestCase.links_with | ( | self, | |
| urdf, | |||
| predicate | |||
| ) |
Iterate all links in the URDF and filter with a predicate
@param urdf: The URDF with the links to filter
@param predicate: A function, which gets the link name as argument and which
should return true if the link should be in the list or not
@return: A list of link names matching the predicate
Definition at line 43 of file urdf_test_case.py.
| def test.urdf_test_case.UrdfTestCase.xacro | ( | self, | |
| file, | |||
args = '' |
|||
| ) |
Generates a URDF from a XACRO file. If the URDF is invalid the test is
automatically failed.
@param file: The name of the xacro input file within `franka_description/robots/`
@param args: A optional string of xacro args to append, e.g. ("foo:=1 bar:=true")
@return: The generated URDF, as urdf_parser_py.urdf.URDF type
Definition at line 9 of file urdf_test_case.py.