From b14b734cf33611edffd4cf43e93be395b857383c Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Tue, 27 Jan 2026 23:27:22 +0100 Subject: [PATCH 1/3] Extend the JointLimit class --- src/urdf_parser_py/urdf.py | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/src/urdf_parser_py/urdf.py b/src/urdf_parser_py/urdf.py index 41fa2b7..c9fc81f 100644 --- a/src/urdf_parser_py/urdf.py +++ b/src/urdf_parser_py/urdf.py @@ -257,18 +257,25 @@ def __init__(self, rising=None, falling=None): class JointLimit(xmlr.Object): - def __init__(self, effort=None, velocity=None, lower=None, upper=None): + def __init__(self, effort=None, velocity=None, lower=None, upper=None, + acceleration=None, deceleration=None, jerk=None): self.effort = effort self.velocity = velocity self.lower = lower self.upper = upper + self.acceleration = acceleration + self.deceleration = deceleration + self.jerk = jerk xmlr.reflect(JointLimit, tag='limit', params=[ xmlr.Attribute('effort', float), xmlr.Attribute('lower', float, False, 0), xmlr.Attribute('upper', float, False, 0), - xmlr.Attribute('velocity', float) + xmlr.Attribute('velocity', float), + xmlr.Attribute('acceleration', float, False, float('inf')), + xmlr.Attribute('deceleration', float, False, float('inf')), + xmlr.Attribute('jerk', float, False, float('inf')) ]) # FIXME: we are missing __str__ here. From 88ea46627b6eb71ecce70d52d0f65d561796de2e Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Fri, 30 Jan 2026 17:41:26 +0100 Subject: [PATCH 2/3] add test cases for the new limits Signed-off-by: Sai Kishor Kothakota --- src/urdf_parser_py/urdf.py | 2 +- test/test_urdf.py | 198 +++++++++++++++++++++++++++++++++++++ 2 files changed, 199 insertions(+), 1 deletion(-) diff --git a/src/urdf_parser_py/urdf.py b/src/urdf_parser_py/urdf.py index c9fc81f..7112448 100644 --- a/src/urdf_parser_py/urdf.py +++ b/src/urdf_parser_py/urdf.py @@ -478,7 +478,7 @@ def check_valid(self): class Robot(xmlr.Object): - SUPPORTED_VERSIONS = ["1.0"] + SUPPORTED_VERSIONS = ["1.0", "1.1", "1.2"] def __init__(self, name=None, version="1.0"): self.aggregate_init() diff --git a/test/test_urdf.py b/test/test_urdf.py index b78432d..8f0548b 100644 --- a/test/test_urdf.py +++ b/test/test_urdf.py @@ -377,5 +377,203 @@ def test_new_urdf_with_version(self): self.assertEqual(testcase.get('version'), '1.0') +class TestJointLimitVersioning(unittest.TestCase): + """Tests for version-based validation of acceleration, deceleration, and jerk.""" + + @mock.patch('urdf_parser_py.xml_reflection.on_error', + mock.Mock(side_effect=ParseException)) + def parse(self, xml): + return urdf.Robot.from_xml_string(xml) + + def test_version_1_0_with_acceleration_fails(self): + xml = ''' + + + + + + + + +''' + self.assertRaises(ValueError, self.parse, xml) + + def test_version_1_0_with_deceleration_fails(self): + xml = ''' + + + + + + + + +''' + self.assertRaises(ValueError, self.parse, xml) + + def test_version_1_0_with_jerk_fails(self): + xml = ''' + + + + + + + + +''' + self.assertRaises(ValueError, self.parse, xml) + + def test_version_1_1_with_acceleration_fails(self): + xml = ''' + + + + + + + + +''' + self.assertRaises(ValueError, self.parse, xml) + + def test_version_1_1_with_deceleration_fails(self): + xml = ''' + + + + + + + + +''' + self.assertRaises(ValueError, self.parse, xml) + + def test_version_1_1_with_jerk_fails(self): + xml = ''' + + + + + + + + +''' + self.assertRaises(ValueError, self.parse, xml) + + def test_version_1_0_without_new_limits_succeeds(self): + xml = ''' + + + + + + + + +''' + robot = self.parse(xml) + self.assertIsNotNone(robot) + self.assertEqual(robot.joints[0].limit.effort, 100) + self.assertEqual(robot.joints[0].limit.velocity, 10) + + def test_version_1_1_without_new_limits_succeeds(self): + xml = ''' + + + + + + + + +''' + robot = self.parse(xml) + self.assertIsNotNone(robot) + self.assertEqual(robot.joints[0].limit.effort, 100) + self.assertEqual(robot.joints[0].limit.velocity, 10) + + def test_version_1_2_with_acceleration_succeeds(self): + xml = ''' + + + + + + + + +''' + robot = self.parse(xml) + self.assertIsNotNone(robot) + self.assertEqual(robot.joints[0].limit.acceleration, 5.0) + + def test_version_1_2_with_deceleration_succeeds(self): + xml = ''' + + + + + + + + +''' + robot = self.parse(xml) + self.assertIsNotNone(robot) + self.assertEqual(robot.joints[0].limit.deceleration, 3.0) + + def test_version_1_2_with_jerk_succeeds(self): + xml = ''' + + + + + + + + +''' + robot = self.parse(xml) + self.assertIsNotNone(robot) + self.assertEqual(robot.joints[0].limit.jerk, 200.0) + + def test_version_1_2_with_all_new_limits_succeeds(self): + xml = ''' + + + + + + + + +''' + robot = self.parse(xml) + self.assertIsNotNone(robot) + self.assertEqual(robot.joints[0].limit.acceleration, 5.0) + self.assertEqual(robot.joints[0].limit.deceleration, 3.0) + self.assertEqual(robot.joints[0].limit.jerk, 200.0) + + def test_version_1_2_without_new_limits_uses_defaults(self): + xml = ''' + + + + + + + + +''' + robot = self.parse(xml) + self.assertIsNotNone(robot) + self.assertEqual(robot.joints[0].limit.acceleration, float('inf')) + self.assertEqual(robot.joints[0].limit.deceleration, float('inf')) + self.assertEqual(robot.joints[0].limit.jerk, float('inf')) + + if __name__ == '__main__': unittest.main() From 85f3a3f505b098fc52f8235feec3c2309c4a01bd Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Fri, 30 Jan 2026 17:41:52 +0100 Subject: [PATCH 3/3] make sure that new limits work with 1.2 --- src/urdf_parser_py/urdf.py | 20 ++++++++++++++++++++ 1 file changed, 20 insertions(+) diff --git a/src/urdf_parser_py/urdf.py b/src/urdf_parser_py/urdf.py index 7112448..5d67fc1 100644 --- a/src/urdf_parser_py/urdf.py +++ b/src/urdf_parser_py/urdf.py @@ -563,6 +563,26 @@ def post_read_xml(self): if self.version not in self.SUPPORTED_VERSIONS: raise ValueError("Invalid version; only %s is supported" % (','.join(self.SUPPORTED_VERSIONS))) + # Validate that acceleration, deceleration, and jerk are only used in version 1.2+ + major = int(split[0]) + minor = int(split[1]) + + if major == 1 and minor < 2: + for joint in self.joints: + if joint.limit is not None: + if joint.limit.acceleration is not None and joint.limit.acceleration != float('inf'): + raise ValueError( + "Joint '%s': acceleration attribute requires URDF version 1.2, " + "but version %s was specified" % (joint.name, self.version)) + if joint.limit.deceleration is not None and joint.limit.deceleration != float('inf'): + raise ValueError( + "Joint '%s': deceleration attribute requires URDF version 1.2, " + "but version %s was specified" % (joint.name, self.version)) + if joint.limit.jerk is not None and joint.limit.jerk != float('inf'): + raise ValueError( + "Joint '%s': jerk attribute requires URDF version 1.2, " + "but version %s was specified" % (joint.name, self.version)) + xmlr.reflect(Robot, tag='robot', params=[ xmlr.Attribute('name', str),