Universal_Robots_ROS_Driver icon indicating copy to clipboard operation
Universal_Robots_ROS_Driver copied to clipboard

UR joints are overshooting

Open fusano opened this issue 3 years ago • 16 comments

Hi.

I have a question about the UR interface. I am currently operating a UR5e and the UR joints are overshooting. As shown in the video in the link, the robot hand is controlled to draw a 15cm radius, 45-degree arc around a plastic bottle cap. The graph in the link compares /joint_states with the results of the inverse kinematics calculation for Wrist3. The speed limit is 30% and angular velocity is about 1/6*π(rad/s). You can see that the joint state of wrist3 overshoots the calculation result from the inverse kinematics and then decays.

Do you know of a solution to this kind of joint angle overshoot?

Thanks.

https://docs.google.com/presentation/d/15Ps2lR6ar5c-hlQDPRVVNG2Tg6TAfJNH/edit?usp=sharing&ouid=112638410209868880665&rtpof=true&sd=true

fusano avatar Jul 02 '22 00:07 fusano

We confirmed that this motion is due to the overshooting from the shoulder_lift and shoulder_pan joint.

This would be problematic since we want to hold a bottle of water.

shoulder_lift_angle shoulder_lift_angle

shoulder_pan_angle shoulder_pan_angle

Overshooting 771e3a974c4dcf9954f0554052ddd469

We are sending our joint position commands to /scaled_pos_joint_traj_controller/command, and speed scaling is 30 %. Increasing the speed scaling might be helpful, but the robot motion becomes shaking and not stable. We also tried to send commands to /pos_joint_traj_controller/command, but the problem still exists.

Is this because the robot driver is doing some interpolation inside the UR scripts?

This problem is similar to #275, and their solution is to slowdown the trajectory. However, we would not like to slow down our trajectory, since it is coming from human teleoperation, the faster the better.

Is there any solution? Or any parameters can be changed?

DavidYaonanZhu avatar Jul 06 '22 09:07 DavidYaonanZhu

Hi, @fmauch, long time no see since Beta release :) Can you kindly look into the matter?

Thank you in advance.

DavidYaonanZhu avatar Jul 06 '22 09:07 DavidYaonanZhu

Hi, @fmauch, long time no see since Beta release :) Can you kindly look into the matter?

Thank you in advance.

You could try to play with servo gain and look ahead time (use lower gain and higher look ahead time) to deal with overshoot.

shuobh avatar Jul 07 '22 21:07 shuobh

Hi, @fmauch, long time no see since Beta release :) Can you kindly look into the matter? Thank you in advance.

You could try to play with servo gain and look ahead time (use lower gain and higher look ahead time) to deal with overshoot.

Hi, where can I find those parameters? in URscript or cpp implementation?

DavidYaonanZhu avatar Jul 08 '22 01:07 DavidYaonanZhu

You can set those in the driver launch file.

On Jul 7, 2022, at 6:39 PM, DavidYaonanZhu @.***> wrote:

 Hi, @fmauch, long time no see since Beta release :) Can you kindly look into the matter? Thank you in advance.

You could try to play with servo gain and look ahead time (use lower gain and higher look ahead time) to deal with overshoot.

Hi, where can I find those parameters? in URscript of cpp implementation?

— Reply to this email directly, view it on GitHub, or unsubscribe. You are receiving this because you commented.

shuobh avatar Jul 08 '22 01:07 shuobh

Hi @shuobh I tried to change servo gain and look ahead time.

I changed the italicized part of the script(the ur_robot_driver/src/ros/hardware_interface.cpp).

`//int servoj_gain = robot_hw_nh.param("servoj_gain", 2000); int servoj_gain = 200; if ((servoj_gain > 2000) || (servoj_gain < 100)) { ROS_ERROR_STREAM("servoj_gain is " << servoj_gain << ", must be in range [100, 2000]"); return false; }

// Specify lookahead time for servoing to position in joint space. // A longer lookahead time can smooth the trajectory. //double servoj_lookahead_time = robot_hw_nh.param("servoj_lookahead_time", 0.03); double servoj_lookahead_time = 0.19; if ((servoj_lookahead_time > 0.2) || (servoj_lookahead_time < 0.03)) { ROS_ERROR_STREAM("servoj_lookahead_time is " << servoj_lookahead_time << ", must be in range [0.03, 0.2]"); return false; }

The following graphs show the result of shoulder lift angles(LEFT: servoj_gain = 2000, servoj_lookahead_time = 0.03 RIGHT: servoj_gain = 200, servoj_lookahead_time = 0.19 ). shouler_lift_angle

There are no change in results. Do you have another way to solve this problem?

Thanks.

fusano avatar Jul 11 '22 06:07 fusano

May I ask why you are using a JointTrajectoryController when you are trying to implement human teleoperation?

You now have <your system> -> <joint_traj_controller> -> <ur_cb_internal_controller>. Those last two are going to be interpolating every motion you send to them.

What sort of references are you sending the JointTrajectoryController? If it's high-frequency joint positions (in short JointTrajectory msgs), I'd suggest using the JointGroupPositionController instead.

That will not do any interpolation for you -- so you are responsible for motion smoothness and continuity -- but for tele-operation tasks, that's much more suitable.

gavanderhoorn avatar Jul 11 '22 06:07 gavanderhoorn

Hi @gavanderhoorn

I want to try the JointGroupPositionController. Could you tell me where I refer?

Thanks.

fusano avatar Jul 11 '22 06:07 fusano

May I ask why you are using a JointTrajectoryController when you are trying to implement human teleoperation?

You now have <your system> -> <joint_traj_controller> -> <ur_cb_internal_controller>. Those last two are going to be interpolating every motion you send to them.

What sort of references are you sending the JointTrajectoryController? If it's high-frequency joint positions (in short JointTrajectory msgs), I'd suggest using the JointGroupPositionController instead.

That will not do any interpolation for you -- so you are responsible for motion smoothness and continuity -- but for tele-operation tasks, that's much more suitable.

Thanks for reply @gavanderhoorn

Does JointGroupPositionController already implemented in this driver? or do we have to implement by ourselves?

Eventhough, changing servo gain and look ahead time should modify the trajectory, it is strange that you get no change (exactly same output ....)

DavidYaonanZhu avatar Jul 11 '22 07:07 DavidYaonanZhu

Please have a look at our controller documentation.

Indeed, sending trajectories to the trajectory controller's command topic with a high frequency isn't the very best choice, as that controller creates interpolation segments each time, as mentioned by @gavanderhoorn above.

fmauch avatar Jul 11 '22 08:07 fmauch

I read controller documentation. But that documentation did not describe JointGroupPositionController.(joint_group_vel_controller is in your documentation)

I only found joint_group_velocity_controller, but I would like to operate UR by position control.

  1. Is the joint_group_velocity_controller implemented or I have to implement by myself?
  2. If I use joint trajectory controller, is there any way to execute joint commands without interpolation? like changing some parameters?

fusano avatar Jul 11 '22 10:07 fusano

@fmauch @gavanderhoorn Would it just add some lines regarding jointgrouppositioncointroller inside .yaml file https://github.com/UniversalRobots/Universal_Robots_ROS_Driver/blob/2e44f8629f6332c1a88361e7a202fad8d99dff00/ur_robot_driver/config/ur5e_controllers.yaml ?

DavidYaonanZhu avatar Jul 12 '22 01:07 DavidYaonanZhu

Hi @fmauch, @gavanderhoorn

We tried the joint_group_pos_controller as suggested by @gavanderhoorn, However, it still has overshooting.

There must be some inner interpolation running inside URScripts.

Could you tell me the solution how to remove this interpolation?

Please kindly look into the matter. Thanks

fusano avatar Jul 13 '22 08:07 fusano

def extrapolate():
  diff = [cmd_servo_q[0] - cmd_servo_q_last[0], cmd_servo_q[1] - cmd_servo_q_last[1], cmd_servo_q[2] - cmd_servo_q_last[2], cmd_servo_q[3] - cmd_servo_q_last[3], cmd_servo_q[4] - cmd_servo_q_last[4], cmd_servo_q[5] - cmd_servo_q_last[5]]
  cmd_servo_q_last = cmd_servo_q
  cmd_servo_q = [cmd_servo_q[0] + diff[0], cmd_servo_q[1] + diff[1], cmd_servo_q[2] + diff[2], cmd_servo_q[3] + diff[3], cmd_servo_q[4] + diff[4], cmd_servo_q[5] + diff[5]]

  return cmd_servo_q
end

I found those lines inside URScript, is this doing interpolation?

fusano avatar Jul 13 '22 08:07 fusano

Hi, @fmauch, @gavanderhoorn

We tried to increase the speed scaling bar on the pendant to 60%, and the overshooting seems to be suppressed.

So, there would be no choice but to regulate the cartesian command velocity?

I guess there might be some null space constraints that can be added, which uses the other joints to compensate for delayed wrist and elbow velocities.

In addition, I wonder why:

  1. I changed ros_control.urscript servoj(gain, look_ahead_time), however, I could not see any change in robot behavior.
  2. What is the speed scaling bar doing specifically? Does it modify the trajectory by it self?

Waiting for your reply, Thanks in advance.

DavidYaonanZhu avatar Jul 14 '22 01:07 DavidYaonanZhu

@fusano using the joint_group_pos_controller should indeed reduce the motion's influence to the controller running on the robot as that controller simply "forwards" the commands to the robot.

And no, the extrapolate function does not interpolate. It extrapolates the ongoing motion in case there's a missed package from the ROS side. This is there to prevent hickups in motion when the network connection is not completely reliable.

@DavidYaonanZhu changing the speed slider shouldn't change anything on that, as to my knowledge it only "stretches" time virtually. The robot should be doing the exact same thing it would if the slider was on 100% but only slower.

fmauch avatar Jul 26 '22 07:07 fmauch

This issue has not been updated for a long time. If no further updates are added, this will be closed automatically. Comment on the issue to prevent automatic closing.

github-actions[bot] avatar Jan 24 '23 22:01 github-actions[bot]

This issue has been closed due to inactivity. Feel free to comment or reopen if this is still relevant.

github-actions[bot] avatar Feb 23 '23 22:02 github-actions[bot]