Skip to content

Commit a1ba6df

Browse files
authored
Restored compatibility with Orocos KDL after Joint.None was removed (#45)
1 parent 735d562 commit a1ba6df

File tree

1 file changed

+3
-1
lines changed

1 file changed

+3
-1
lines changed

kdl_parser_py/kdl_parser_py/urdf.py

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -50,7 +50,9 @@ def _toKdlInertia(i):
5050

5151
def _toKdlJoint(jnt):
5252

53-
fixed = lambda j,F: kdl.Joint(j.name, getattr(kdl.Joint, 'None'))
53+
fixed = lambda j,F: kdl.Joint(
54+
j.name,
55+
getattr(kdl.Joint, 'Fixed') if hasattr(kdl.Joint, 'Fixed') else getattr(kdl.Joint, 'None'))
5456
rotational = lambda j,F: kdl.Joint(j.name, F.p, F.M * kdl.Vector(*j.axis), kdl.Joint.RotAxis)
5557
translational = lambda j,F: kdl.Joint(j.name, F.p, F.M * kdl.Vector(*j.axis), kdl.Joint.TransAxis)
5658

0 commit comments

Comments
 (0)