ros-industrial / abb_libegm

A C++ library for interfacing with ABB robot controllers supporting Externally Guided Motion (689-1)
BSD 3-Clause "New" or "Revised" License
93 stars 53 forks source link

Question about EGM tracking speed and accuracy #111

Closed Wojcik98 closed 3 years ago

Wojcik98 commented 3 years ago

I have been testing how fast can the EGM track received positions and how much the current position deviates from it. Tests were in pose mode, all parameters with default values except MaxSpeedDeviation which was 10'000 to not limit the movement. Trajectory used (x, y, z values):

I tested it with different speeds (or rather duration times using EGMTrajectoryInterface) and plotted the difference between desired and actual position (from libegm logging S_REF_POS_<coord> - R_FB_POS_<coord>).

The biggest error was over 15cm and for lower speeds the typical error was still over 3cm. Those are quite large considering EGM is supposed to be used for real-time control. Are those errors expected? I have tried to increase Default Proportional Position Gain to 12. It slightly reduced the error, but introduced overshoot and small oscillations. Setting gain to 20 further decreased the error and increased oscillations.

Is there a way to reduce those errors? Is it possible it is caused by wrong settings? Maybe controlling with velocities instead of position could be a better solution?

I am using RobotStudio with RobotWare 6.11.2019.

marekcygan commented 3 years ago

@jontje any chance that you could comment on the issue above? We are looking now into velocity control to check discrepancies there.

jontje commented 3 years ago

It's been awhile since I used the EGMTrajectoryInterface, but here are a few things you could investigate:

I hope this can help!

marekcygan commented 3 years ago

@jontje we will definitely try those and get back to you, thanks!

Wojcik98 commented 3 years ago

Thanks for suggestions @jontje! Disabling filtering removed majority of oscillations and slightly reduced error. We could then safely increase position gain to 20 which decreased the error even further with only small overshoot.

Enabling velocity outputs also significantly reduced error.

In the end the error was reduced from over 100mm to below 25mm, and it was caused mainly by latency between sending position and robot executing it. After shifting desired and measured trajectories by a few samples to account for latency the errors are even smaller. (plot below shows only y axis)

Thanks again for your help.

jontje commented 3 years ago

Thanks for suggestions @jontje!

No problem, I'm happy to help 😄

mkatliar commented 2 years ago

Hello,

I have some new questions about EGM.

We use EGM for joint trajectory following, and our trajectories are quite fast. We provide both joint position and velocity reference to EGM, and use the "Raw" correction level. Below are examples of how the same reference trajectory is followed for different proportional position gain values:

Figure 1. gain=10 p_10

Figure 2. gain=5 p_05

Figure 3. gain=1 p_01

Figure 4. gain=0 p_00

In all cases, trajectory tracking is far from perfect. For gain=0 we achieve very good velocity tracking, but the position trajectory is shifted. There seems to be a dead time of ~50ms (Figure 5), which results in the velocity commands at the beginning of the trajectory being ignored, and therefore offset in the position. Also, without position gain, the position is expected to drift anyway.

Figure 5. Dead time image

Adding a small position gain results in a significant deviation from the reference trajectory, and very slow convergence to the final position after the motion has ended (Figure 3).

Do you guys have any idea on how we can improve the trajectory tracking? @jontje could you help?

I have also noticed that there is a time field in the EgmPlanned message:

message EgmPlanned              // Planned  position for robot (joints or cartesian) and additional axis (array of 6 values)
{                               // Is used for position streaming (source: controller) and position guidance (source: sensor)
    optional EgmJoints  joints = 1;
    optional EgmPose    cartesian = 2;
    optional EgmJoints  externalJoints = 3;
    optional EgmClock   time = 4;
}

but I could not find in the documentation what it is for. I guess it can be related to specifying the reference ahead in time and can be used to deal with the dead time / trajectory offset. Do you know how is this field used?