Interbotix / interbotix_ros_arms

ROS packages for the InterbotiX X-series family of robotic arms and turrets
BSD 2-Clause "Simplified" License
49 stars 27 forks source link

Decrease error between robot and goal pose #28

Closed TaekedeHaan closed 4 years ago

TaekedeHaan commented 4 years ago

I use MoveIt in combination with the interbotix_sdk to command the px150 to a desired pose or joint state. I use position control with the default PID and feedforward values. As can be seen from the figure below, the robot is not always able to get near the goal pose. This is generally the case for poses which require a large torque from the motors.

issue

I noticed that their are various manners how I can try to reduce this error:

  1. Use the arm in position control, and tune the internal PID gains of the DYNAMIXELS.
  2. Use the arm in velocity control, and use the provided PID controls from the interbotix_sdk, possibly in combination with tuning the internal PI gains of the DYNAMIXELS.
  3. Modifying the goal pose by adding a small value to the pose height, this value should increase the further away the goal pose is from the robot base.

I was only able to get some improvements with the third approach. However it feels a bit ugly, as the cause of the problems seems to lie in the controllers. I noticed that tightening the controls can cause a Shutdown error on the DYNAMIXEL, making tuning a tedious proces. I was wondering whether you would recommend an approach over the other, or have a possible solution I overlooked.

swinterbotix commented 4 years ago

Hi @TaekedeHaan,

Those three choices you mentioned are definitely viable options. From a design perspective, I'd say that the best approach is the first one you mentioned. Like you said, the third approach is very hacky, and I'm actually planning on pulling the second option from the sdk on a future update (not to this repo, but in a different repo). The main reason I implemented the second option is because at the time, I was having issues getting the internal motor PID gains to function correctly.

About the 'shudown errors'...

My guess is that you're seeing these errors mostly in the shoulder and elbow joints? What might be happening is that the two motors that make up each of those joints are 'fighting' each other. For example, one of the elbow motors might be showing 0.25 degrees while the one opposite is showing -0.25 degrees. As a result, the more you increase the PID gains for that joint, the more each of those motors will try to 'fight' each other, potentially stressing out the motors and causing shutdown errors due to 'overload'. To correct for this, you can use the Dynamixel Wizard 2 tool to look at the 'Present_Position' registers for the two motors that make up each dual-joint. If the difference between them is more than a couple ticks (remember - there are 4096 ticks in one revolution), then I'd suggest tuning the 'Homing_Offset' register (essentially tweaks the 'zero' position of the motor) for the 'shoulder_shadow' or 'elbow_shadow' motors (as defined here). For example, tune the 'shoulder_shadow' servo Homing_Offset register until its Present_Position register matches that of the 'shoulder' servo. This way, if you tune high PID gains, the motors that make up each joint will work together better instead of fighting each other - reducing the chance of 'overload' errors.

Note that in a future update, this calibration step will happen automatically at startup.

TaekedeHaan commented 4 years ago

Thanks a lot for your help. The shadow motors were of by approximately 10 ticks. After re-calibration the overload error happens less frequently. Nice to hear that this will be included in a future update.

As suggested I decided to use the arm in position control, and tune the internal PID gains of the DYNAMIXELS. Increasing the P values helps, as can be seen from the image below.

image