fzi-forschungszentrum-informatik / cartesian_controllers

A set of Cartesian controllers for the ROS1 and ROS2-control framework.
BSD 3-Clause "New" or "Revised" License
397 stars 119 forks source link

Arm is oscillating in steady state #177

Open kirtan-raise opened 8 months ago

kirtan-raise commented 8 months ago

Hi! Thank you to the authors for this wonderful controllers. I have been using Cartesian compliance controllers for diverse peg in hole applications and it has been very useful.

System Details. UR20 arms. Using inbuilt Force torque sensor at the frame tool0. Payload details.
mass(kg) : 10.94 cog(m) : x: 0.042, y: -0.223, z: 0.229 (This is is in tool0 frame)

image

Description. Currently. what I have been observing is that arm is oscillating at the steady state in Cartesian compliance and Cartesian motion Controller. For Cartesian motion controller I have been able to reduce the oscillations with higher iterations and error scale values. for now, I have kept error scale at 5 and iteration to 15. Oscillation competently dies down as I further increase these two values. Now, I am not able to use similar tuning fort compliance controller. For now, error scale is at 0.002 and iterations is at 1. If I go further higher than this arm shakes and goes to protective stop.

Possible Cause and Solutions.

  1. Force torque sensor is quite away from the cog of the payload and controller is reacting to oscillations in the wrench values. For that I added a low pass filter on observed wrench and that helped. But downside of that will be that filtered data has lag compared to unfiltered data. So, there is some limit to how much I can filter. Another solution could be to have an additional sensor much closer to payload cog and that will reduce the oscillations in the observed wrench values.
  2. For I now I do not have mass and inertial details in the xacro files for the end effector. May be higher value of payload is enough to contribute to forward dynamics calculations and leading to oscillations. I am working on this right now.

I would appreciate the insights from the community on possible causes or some ideas to try on to reduce the oscillations.

Update 1: I tested the Cartesian compliance controller without any end effector i.e payload mass =0, cog = {0, 0 , 0}, and without any filters on the force torque sensor data. Arm is showing similar oscillations as with the heavy end effectors mentioned earlier.

Video Link: https://photos.app.goo.gl/EYZ8aSfdeUEqDzog8

Thank you.

shrutichakraborty commented 8 months ago

Hi @kirtan-raise I have similar issue with the cartesian motion controller. I am using a UR10e robot with ros2 humble and the default values for the PID gains and error scales. On commanding a cartesian pose, once the robot reaches the commanded point there is some oscillation of the end effector at the end of the trajectory. Furthermore with the cartesian force controller there is a deviation in x,y position when I command a wrench purely in z. Any ideas from @fmauch @bmagyar or others on which parameters to tune and ideal values (if any have been found by the community that would be great to know? Additionally has anyone had any experience comparing the performance of the cartesian controllers compared to moveit?

Thank you!

kirtan-raise commented 8 months ago

Hi @shrutichakraborty, I can give some insight on tuning motion controller. Default values may or may not be good for your setup. I would suggest tweaking error scale and iteration values. As you increase them arm will start behaving more and more like an inverse kinematics solver and try to reach the target pose a lot faster. To give some idea on values, I started with error scale=0.1, iteration=1 and now I am at error scale=5 and iteration=11. I would suggest to look at the current pose real time data in rqt_plot as you increase the values and check if oscillation amplitude goes down. On the side note, at this higher tuned values I added more target frame way points from current pose to goal pose so that I do not see sudden jerky motion. I am publishing target frame at close to 100 Hz.

shrutichakraborty commented 7 months ago

Hi @shrutichakraborty, I can give some insight on tuning motion controller. Default values may or may not be good for your setup. I would suggest tweaking error scale and iteration values. As you increase them arm will start behaving more and more like an inverse kinematics solver and try to reach the target pose a lot faster. To give some idea on values, I started with error scale=0.1, iteration=1 and now I am at error scale=5 and iteration=11. I would suggest to look at the current pose real time data in rqt_plot as you increase the values and check if oscillation amplitude goes down. On the side note, at this higher tuned values I added more target frame way points from current pose to goal pose so that I do not see sudden jerky motion. I am publishing target frame at close to 100 Hz.

Thanks a lot, I having tweaked the number of iterations and am now at 12, and increased the p gain of the trans_z parameter to 1.6. I still see a behaviour where the robot reaches the commanded position and then shakes a bit around the end effector which makes the behaviour look quite unstable. I am not sure which parameters could be causing this (any ideas @fmauch , @fzi-admin ?). I am having trouble understanding how to tweak the error scale? Would larger error scale allow larger error between commanded and reached pose?

Also sometimes, the stopping the controller on the computer causes the robot to start moving randomly, this is dangerous. How can it be avoided?

stefanscherzinger commented 6 months ago

@kirtan-raise

I tested the Cartesian compliance controller without any end effector i.e payload mass =0, cog = {0, 0 , 0}, and without any filters on the force torque sensor data. Arm is showing similar oscillations as with the heavy end effectors mentioned earlier. Video Link: https://photos.app.goo.gl/EYZ8aSfdeUEqDzog8

Thank you for uploading a video, that's helpful! I'm unsure why this happens but I can confirm that I know these small movements on the URe robots when using the cartesian_force_controller. I didn't give it much thought, because they usually disappeared when in contact with the environment. However, you're right. They shouldn't be there. I would set iterations = 1. You could also try the velocty-based version. I think the UR driver uses a different command and interpolation technique when using velocities. Also see these insights here.

stefanscherzinger commented 6 months ago

@shrutichakraborty

I am having trouble understanding how to tweak the error scale? Would larger error scale allow larger error between commanded and reached pose?

The higher the error_scale, the stronger is the error rejection in the controller. There's no allowed error between the commanded reference and the controlled variable. All controllers have a built-in integrator, so they will eliminate steady state errors. Here's a brief documentation.

Also sometimes, the stopping the controller on the computer causes the robot to start moving randomly, this is dangerous. How can it be avoided?

This should definitely not be the case. Could you provide a small video that shows this? There's something wrong. Let's debug this.

kirtan-raise commented 6 months ago

Thank you @stefanscherzinger for your response and @shrutichakraborty for your updates.

Thank you for uploading a video, that's helpful! I'm unsure why this happens but I can confirm that I know these small movements on the URe robots when using the cartesian_force_controller. I didn't give it much thought, because they usually disappeared when in contact with the environment. However, you're right. They shouldn't be there.

Just a little note on this. Last year I was working on the Ur10e and I did not notice this small movements on it. For me it is more specific to Ur20. Yes, you are right when it has any target position or force (while in motion) or in contact oscillations go away.

I would set iterations = 1.

Just curious on this suggestion. I believe reducing error scale will further require iteration to go up for similar performance.

You could also try the velocty-based version. I think the UR driver uses a different command and interpolation technique when using velocities.

Thank you for this suggestion. I observed that at error_scale=0.0002 and iterations = 1 end effector is stable but very less compliant. At error_scale=0.002 and iterations = 1 end effector has high frequency oscillations (compared to position-based version). Compliance is higher at higher error scale but not as complaint as with position-based controller. So, I think in my case as I am looking for higher compliance position-based control seems better fit. I believe it could help with the cartesian_motion_controller. Yet, to be tested though.

This should definitely not be the case. Could you provide a small video that shows this? There's something wrong. Let's debug this.

I have observed this also. Arm, moves right after I change the controller from Cartesian compliance controller to 'pos_joint_traj_controller'. Its type is 'position_controllers/JointTrajectoryController' I attaching a video with plots for us to debug it better. From, what I have seen it is happening after the compliance controller has stopped and pos_joint_traj_controller has started. It happens with Cartesian_motion and Cartesian_compliance controllers. So, payload can not be an issue.

https://photos.app.goo.gl/zfmWXqqpVQmuXh3j6

LAYERED-pierrechass commented 2 weeks ago

Hello, First, thanks a lot for the controllers it is really great work! I just setup an UR10e with the Compliance controller on ROS! Noetic with default controller values and I noticed the same small oscillations at rest. I didn't try to tweak the parameters yet. I aslo have a tool with an offset in COG, but I didn't set the COG on the arm (this might be what is causing the issue).

For I now I do not have mass and inertial details in the xacro files for the end effector. May be higher value of payload is enough to contribute to forward dynamics calculations and leading to oscillations. I am working on this right now.

Have you been able to investigate this? Did it yield better results?

I don't think it should be an issue for me as long as it remains small oscillations. Just thought I would document that as I am seeing this behavior as well. Let me know if I can help with anything. :)

System Details. UR10e arm. Using inbuilt Force torque sensor at the frame tool0. Payload details. mass(kg) : ~1kg cog(m) : Didn't measure it so set to {0,0,0} but cf picture.

WhatsApp Image 2024-11-04 at 14 22 50