Skip to content

Commit f1d1273

Browse files
committed
Passes client ID to PyBullet functions for Multi-client IK
Ensures that the correct physics client is used when resetting joint states and retrieving link states in the inverse kinematics calculation, which is crucial for multi-client setups.
1 parent bebbf0f commit f1d1273

1 file changed

Lines changed: 3 additions & 2 deletions

File tree

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

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -729,13 +729,14 @@ def _accurate_inverse_kinematics(
729729
# https://github.com/bulletphysics/bullet3/blob/master/examples/pybullet/examples/inverse_kinematics.py
730730
# kwargs["maxNumIterations"] = max_iter
731731
# kwargs["residualThreshold"] = threshold
732+
client_id = kwargs["physicsClientId"]
732733

733734
for i in range(max_iter):
734735
joint_poses = pybullet.calculateInverseKinematics(**kwargs)
735736
for i in range(len(joint_ids_sorted)):
736-
pybullet.resetJointState(body_id, joint_ids_sorted[i], joint_poses[i])
737+
pybullet.resetJointState(body_id, joint_ids_sorted[i], joint_poses[i], physicsClientId=client_id)
737738
# Retrieve the last link state that contains the last link's position (index 4) and orientation (index 5)
738-
link_state = pybullet.getLinkState(body_id, link_id)
739+
link_state = pybullet.getLinkState(body_id, link_id, physicsClientId=client_id)
739740

740741
# Check tolerance_position
741742
new_position = link_state[4]

0 commit comments

Comments
 (0)