Interbotix / interbotix_ros_manipulators

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

[Question]: Using the gripper servo on the px100 as just another joint #20

Closed emmazhou closed 2 years ago

emmazhou commented 2 years ago

Question

Hello! I have a px100 on which I've replaced the gripper hardware with a custom-printed part. It looks like (at least from the python library) there's no way to continuously move the gripper servo like the others, only open/close.

What's the easiest way to treat servo 5 as just another servo, so that it works with e.g. set_joint_positions? I've tried editing the config yaml file, but that just confuses the GUI and gave me an index out of bounds error in python.

Thanks!! Otherwise really enjoying playing with the robot so far :)

Robot Model

px100

Operating System

A fresh install of Ubuntu 20.04, following instructions from this repo

Anything Else

No response

lukeschmitt-tr commented 2 years ago

Hi @emmazhou! There's not an officially supported way to do this, though it is possible. You'll have to create a new "robot" for it to work how you want. Please do the following:

  1. Duplicate the px100 motor config file and name it something unique.
  2. In the new motor config file, add gripper to the list of joints in the arm group and remove the list of grippers. Change the configs of the gripper joint as needed.
    • The top of your motor config file should look something like:
      
      port: /dev/ttyDXL

joint_order: [waist, shoulder, elbow, wrist_angle, gripper] sleep_positions: [0, -1.88, 1.5, 0.8, 0]

joint_state_publisher: update_rate: 100 publish_states: true topic_name: joint_states

groups: arm: [waist, shoulder, elbow, wrist_angle, gripper]

shadows:

sisters:

...


3. Modify any the px100 URDF (and SRDF if you plan to use MoveIt) so it matches your new arm and name them the same as your motor config file. Make sure to add upper and lower limits to the joint that replaces `gripper`.
4. Create a new class in [mr_descriptions.py](https://github.com/Interbotix/interbotix_ros_toolboxes/blob/main/interbotix_xs_toolbox/interbotix_xs_modules/src/interbotix_xs_modules/mr_descriptions.py) with the same name as your robot and modify it so it matches the FK of your robot (add a new screw axis row to the Slist and change M so it represents your new "end effector" position and orientation).
5. When creating an InterbotixManipulatorXS object from the Python API, set `gripper_name=None`.

We haven't officially released instructions on anything like this before so there may be some additional steps that we missed. If you encounter any issues, just let us know.
emmazhou commented 2 years ago

Thanks for the quick response! For step 3, where does the URDF live? Do I need to change something on the robot itself?

I tried steps 2, 4, and 5 without adding a new name, just modifying files in place, and I got to a state where everything started up with no errors, however when I try set_single_joint_position('gripper', k) and k is anything but 0, the method returns False and the robot doesn't move.

I edited the config file as suggested in your code snippet, and here's what I changed mr_descriptions.py to:

class px100:
    Slist = np.array([[0.0, 0.0, 1.0, 0.0, 0.0, 0.0],
                      [0.0, 1.0, 0.0, -0.0931, 0.0, 0.0],
                      [0.0, 1.0, 0.0, -0.1931, 0.0, 0.035],
                      [0.0, 1.0, 0.0, -0.1931, 0.0, 0.135]
                      [1.0, 0.0, 0.0, 0.0, 0.1931, 0.0]]).T

Does that look correct?

Thanks again for your help!

lukeschmitt-tr commented 2 years ago

The URDF lives in the interbotix_xsarms_descriptions package. Here is a direct link to the px100 urdf xacro file.

I suspect that the reason you're getting these errors is that you haven't added upper and lower limits to the px100 urdf's gripper joint and it's defaulting to None or 0. This would result in the check_joint_limits or check_single_joint_limit functions returning False.

I'm not sure about your Slist parameter as I don't know what the kinematics of your robot look like, but you can see how to calculate Slist and M for your new joint using the methods defined in Chapter 4 of Modern Robotics.

swiz23 commented 2 years ago

There's also the mode config file at https://github.com/Interbotix/interbotix_ros_manipulators/blob/main/interbotix_ros_xsarms/interbotix_xsarm_control/config/modes.yaml that you'd want to comment out everything from 'singles' onwards.

It may be setting the gripper servo to operate in 'pwm' mode which is not what you want.

lukeschmitt-tr commented 2 years ago

@emmazhou Do you have any further questions on this topic? This issue will be closed otherwise.