Interbotix / interbotix_ros_manipulators

ROS Packages for Interbotix Arms
BSD 3-Clause "New" or "Revised" License
115 stars 80 forks source link

[Question]: Transformation Matrix to set the body frame to the end of gripper #207

Closed zainabsaeed24 closed 2 weeks ago

zainabsaeed24 commented 1 month ago

Question

Currently the ee_gripper_link is the body frame set in the middle of the robot's gripper. We would like to get a transformation matrix to set the ee_gripper_link/body frame (with respect to the base frame) to the very end of the gripper's away from the base frame. There is matrices defined in mr descriptions python file and we assume that we need to change the numbers accordingly. Could you please help us in this regard?

Pictures attached show the end point of the gripper where we want our body frame\ee_gripper_link to be centered on. viperx viperx_2

Robot Model

No response

Operating System

Ubuntu 20.04

ROS Version

ROS 1 Noetic

Additional Info

No response

lukeschmitt-tr commented 1 month ago

If you simply want the pose of the gripper fingertips wrt to the base, you can multiply the matrix from the output of get_ee_pose() or get_ee_pose_command() by a tranformation matrix with identity rotation and translation in the x-direction with the length of the distance between the ee_gripper_link frame and the gripper fingertip. Let's say you are using the vx300s. Your script would look something like below:

ee_gripper_link_to_fingertip_x = 0.0295

transform = np.array([
    [1.0, 0.0, 0.0, ee_gripper_link_to_fingertip_x],
    [0.0, 1.0, 0.0, 0.0],
    [0.0, 0.0, 1.0, 0.0],
    [0.0, 0.0, 0.0, 1.0],
])

bot.arm.go_to_home_pose()

print('Home')
home = np.dot(
    bot.arm.get_ee_pose_command(),
    transform,
)
print(home)
print(f'x={home[0][3]}')

bot.arm.go_to_sleep_pose()

print('Sleep')
sleep = np.dot(
    bot.arm.get_ee_pose_command(),
    transform,
)
print(sleep)
print(f'x={sleep[0][3]}')

With the output:

Home
[[1.       0.       0.       0.565994]
 [0.       1.       0.       0.      ]
 [0.       0.       1.       0.42705 ]
 [0.       0.       0.       1.      ]]
x=0.565994
Sleep
[[ 0.87758259  0.          0.47942549  0.16297864]
 [ 0.          1.          0.          0.        ]
 [-0.47942549  0.          0.87758259  0.09129842]
 [ 0.          0.          0.          1.        ]]
x=0.1629786412181263

Modifying the mr_descriptions would be a bit more effort and would change the behavior of the Python-ROS API. You can change the URDF to move the ee_gripper_link to your desired position and run our Kinematics from Robot Description tool to generate new M and Slist matrices. Note that this will be the new frame from which ee poses are commanded and received.

zainabsaeed24 commented 2 weeks ago

Thank you so much. This was really helpful.