Skip to content

Commit 47a04f1

Browse files
authored
Merge pull request #234 from compas-dev/pybullet_ik_bug
silly bugs
2 parents 549f25e + f36eff5 commit 47a04f1

File tree

1 file changed

+2
-2
lines changed

1 file changed

+2
-2
lines changed

src/compas_fab/backends/pybullet/backend_features/pybullet_inverse_kinematics.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -62,11 +62,12 @@ def inverse_kinematics(self, robot, frame_WCF, start_configuration=None, group=N
6262
------
6363
:class:`compas_fab.backends.InverseKinematicsError`
6464
"""
65+
options = options or {}
6566
link_name = options.get('link_name') or robot.get_end_effector_link_name(group)
6667
link_id = self.client._get_link_id_by_name(link_name, robot)
6768
point, orientation = pose_from_frame(frame_WCF)
6869

69-
joints = robot.get_configurable_joints()
70+
joints = robot.model.get_configurable_joints()
7071
joints.sort(key=lambda j: j.attr['pybullet']['id'])
7172
joint_names = [joint.name for joint in joints]
7273

@@ -75,7 +76,6 @@ def inverse_kinematics(self, robot, frame_WCF, start_configuration=None, group=N
7576

7677
called_from_test = 'pytest' in sys.modules
7778
if options.get('enforce_joint_limits', True) and not called_from_test:
78-
7979
lower_limits = [joint.limit.lower if joint.type != Joint.CONTINUOUS else 0 for joint in joints]
8080
upper_limits = [joint.limit.upper if joint.type != Joint.CONTINUOUS else 2 * math.pi for joint in joints]
8181
# I don't know what jointRanges needs to be. Erwin Coumans knows, but he isn't telling.

0 commit comments

Comments
 (0)