You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
The docs say that this argument should be "the point on the specified link to compute the jacobian for, in link local coordinates around its center of mass.", which is unclear.
While this example says this argument should be com_rot.T * com_trn.
I checked many ways to compute this argument and compared the results numerically, apparently when the link's inertial frame is drastically different from the URDF's link local frame, the only way to produce correct results (see "link vt" vs "expected link vt" below) is to provide localPosition as the position of the point under URDF link frame's origin but the inertial frame's orientation, as denoted by method1, whereas method2 produces incorrect results.... which matches the example's description.
Can I ask why this has such a weird input format? If I understand correctly the localPosition should be provided as
joint_angles = [x[0] for x in p.getJointStates(robotId, list(range(num_joints)))]
joint_vels = [x[1] for x in p.getJointStates(robotId, list(range(num_joints)))]
for link_idx in range(num_joints):
linkworldpos, linkworldorn, com_trn, com_rot, frame_pos, frame_orn, link_vt, link_vr = p.getLinkState(robotId, link_idx, computeLinkVelocity=True, computeForwardKinematics=1)
com = np.array(p.getMatrixFromQuaternion(com_rot)).reshape(3, 3).T @ np.array(com_trn) # method1, correct
# com = np.array(com_trn) # method2, incorrect
linear_jac, _ = p.calculateJacobian(robotId, link_idx, list(com), list(joint_angles), [1] * num_joints, [0] * num_joints) # [3, num_joints]
if link_idx == num_joints - 2: # pick a joint where the inertial frame orn differs from URDF link frame orn
print("link vt:", link_vt, "expected link vt:", np.asarray(base_R) @ np.asarray(linear_jac) @ np.array(joint_vels))
The text was updated successfully, but these errors were encountered:
The docs say that this argument should be "the point on the specified link to compute the jacobian for, in link local coordinates around its center of mass.", which is unclear.
While this example says this argument should be com_rot.T * com_trn.
I checked many ways to compute this argument and compared the results numerically, apparently when the link's inertial frame is drastically different from the URDF's link local frame, the only way to produce correct results (see "link vt" vs "expected link vt" below) is to provide localPosition as the position of the point under URDF link frame's origin but the inertial frame's orientation, as denoted by method1, whereas method2 produces incorrect results.... which matches the example's description.
Can I ask why this has such a weird input format? If I understand correctly the localPosition should be provided as
The text was updated successfully, but these errors were encountered: