ros-industrial / abb_robot_driver

The new ROS driver for ABB robots
BSD 3-Clause "New" or "Revised" License
100 stars 44 forks source link

Timed out while waiting for EGM feedback (did the EGM session end on the robot controller?) #16

Open robberthofmanfm opened 3 years ago

robberthofmanfm commented 3 years ago

When we launch bringup example 3, we get some warnings about soft limits, but I think those are fine, e.g.: [ WARN] [1614788399.000458960]: Configured default soft limits for 'yumi_robl_joint_7': position [-3.95683; 3.95683], k: 1 What does concern me is that immediately after that, we get the following warnings, with 10 seconds interval between them: [ WARN] [1614783640.237502918]: Timed out while waiting for EGM feedback (did the EGM session end on the robot controller?) And indeed, the EGM session did not start yet, since we are at Idling... state on the robot controller. So what we do is, as the bringup example prescribes,

rosservice call /yumi/rws/stop_rapid "{}"
rosservice call /yumi/rws/pp_to_main "{}"
rosservice call /yumi/rws/start_rapid "{}"
rosservice call /yumi/rws/sm_addin/start_egm_joint "{}"

And then this warning message Timed out while waiting for EGM feedback stops for 60 seconds, as the TeachPendant also prints out Starting joint motion. After 60 seconds, the TeachPendant goes back to Idling... and the terminal prints warnings every 10 seconds again.

What kind of EGM feedback does the bringup_example expect? How can we make sure it gets its feedback? Why is the joint motion stopped after a timeout period?

gavanderhoorn commented 3 years ago

I'm pretty sure you're running into the EGM convergence timeout or idle timeout.

If this

Why is the joint motion stopped after a timeout period?

means "why does Starting joint motion go back to Idling after a timeout of 60 seconds", then it would probably be that convergence timeout.

But this should only happen if your robot is doing nothing.

You should be able to check the state of the EGM channels via the /egm/egm_states topic. The active field should say True whenever EGM is active, and False when you've either disabled the channel yourself (by calling stop_egm) or because the timeout occurred.

You should be able to change the timeout value using the egm settings service. I find it's convenient to retrieve the current settings, changing the values I need to change and the writing them back again (instead of populating all the fields yourself in a from-scratch service request object).


Edit: this is just my interpretation of things, so could be wrong, but: EGM is externally guided motion. So it's supposed to be used to guide motion, ie: when motion is active. Robots sitting idle don't need to be guided, so EGM has done its job and can be shut down.

What kind of EGM feedback does the bringup_example expect?

pedantic, but: the example or .launch file doesn't really expect anything of course. It's the egm_hardware_interface node, as that's the entity communicating with your IRC5 over UDP using the EGM protocol.

How can we make sure it gets its feedback?

don't let the idle timeout expire.

Why is the joint motion stopped after a timeout period?

here we have to be careful: is your robot moving and then the EGM session times out, or is your robot actually idling?

Again: the session should only terminate via the timeout if your robot is actually idling.

gavanderhoorn commented 3 years ago

@jontje: this may be something we need to document better.

It's not specific to this driver, as it's a base EGM behaviour, but it's surprising enough that it would warrant some explanation.

Perhaps just by referring to the relevant sections in the EGM and/or IRC5 manuals though.

robberthofmanfm commented 3 years ago

But this should only happen if your robot is doing nothing.

Robots sitting idle don't need to be guided, so EGM has done its job and can be shut down.

Why is the joint motion stopped after a timeout period?

here we have to be careful: is your robot moving and then the EGM session times out, or is your robot actually idling?

Again: the session should only terminate via the timeout if your robot is actually idling.

It also happens when we plan and execute a motion (using MoveIt) that takes more than 60 seconds. We have a lot of those scenarios because for some reason the robot is moving very slowly. The motion will stop halfway through, we'd have to rosservice call /yumi/rws/sm_addin/start_egm_joint "{}" again, and press Plan and Execute again in MoveIt, and then it will resume moving.

You should be able to change the timeout value using the egm settings service. I find it's convenient to retrieve the current settings, changing the values I need to change and the writing them back again (instead of populating all the fields yourself in a from-scratch service request object).

Thanks, we'll definitely look into that. We didn't think that would be the 'way to go' because we've obviously broken some feedback mechanism in our setup.

robberthofmanfm commented 3 years ago

Can it be that this Timed out while waiting for EGM feedback occurs because we've renamed /yumi/joint_states to /joint_states? I'd test it out but I have no access to the robot today.

gavanderhoorn commented 3 years ago

for some reason the robot is moving very slowly.

the default setting for MaxSpeedDeviation is 0.1 by default. This is mentioned in the Troubleshooting section of the abb_egm_hardware_interface package.

You'll want to change that.

You can again find that in the settings you can change with the EGM settings service.

gavanderhoorn commented 3 years ago

It also happens when we plan and execute a motion (using MoveIt) that takes more than 60 seconds.

hm, this should not happen afaik.

@jontje ?


Edit: with YuMi, there are two channels. Are you using both at the same time, or only one?

robberthofmanfm commented 3 years ago

Edit: with YuMi, there are two channels. Are you using both at the same time, or only one?

Both at the same time, and both go Idling... after 60s, even if both are moving. (IIRC, to be confirmed tomorrow).


Edit: confirmed: both go idling after 60s while both are moving.

gavanderhoorn commented 3 years ago

I've used something like this in the past:

#!/usr/bin/env python3
import rospy
import math

from abb_rapid_sm_addin_msgs.srv import *

rospy.wait_for_service('<some_namespace>/rws/get_egm_settings')
rospy.wait_for_service('<some_namespace>/rws/set_egm_settings')
get_egm_settings = rospy.ServiceProxy("<some_namespace>/rws/get_egm_settings", GetEGMSettings)
set_egm_settings = rospy.ServiceProxy("<some_namespace>/rws/set_egm_settings", SetEGMSettings)

current_settings = get_egm_settings(task='T_ROB1')
settings = current_settings.settings
print (settings)

# max_speed_deviation is in deg/s, we convert from rad/s
settings.activate.max_speed_deviation = math.degrees(3.0)
print (settings)

set_egm_settings(task=taskname, settings=settings)

Be sure to update namespaces, values and add error handling of course.

And be sure to use correct task names.

Note: these settings are not persisted. So you'll have to run something like this every time you restart the StateMachine task(s). If you're not using the services to set these, then settings on the controller side will of course be persisted.

It depends a bit on what you find most convenient and on your safety requirements.

robberthofmanfm commented 3 years ago

Thanks a lot @gavanderhoorn ! Very useful script, the robot speed is indeed much higher now. As far as the EGM feedback timeout goes, I suppose that's not a severe issue anymore since our individual robot movements do not take more than a minute anymore. We'll just call start_egm rosservice call /yumi/rws/sm_addin/start_egm_joint "{}" before planning and executing on MoveIt and rosservice call /yumi/rws/sm_addin/stop_egm "{}" after MoveIt tells us that trajectory execution has completed. Thanks again, your and jontje's help has been crucial in arriving to a working system.

gavanderhoorn commented 3 years ago

We've debated whether we should integrate updating the EGM settings automatically on the controller based on whatever the ROS side 'knows'. However, there are some disadvantages to that:

  1. it would only work if the StateMachine addon is installed (as otherwise there isn't really an easy way to configure the EGM settings)
  2. it doesn't really matter what the ROS side has configured, as the IRC5 holds the absolute truth (ie: we cannot make the controller do things it's been configured not to allow)

These things combined made us not do this by default -- as annoying as having to update the settings every time you start a session is.

Based on user feedback, we may reevaluate that decision though -- perhaps we've overlooked some way of configuring the controller (without relying on the SM Addon) which could help here (using RWS perhaps?).

As far as the EGM feedback timeout goes, I suppose that's not a severe issue anymore since our individual robot movements do not take more than a minute anymore.

no, it is an issue and remains one.

Based on my understanding, EGM sessions should not time out while motions are executing.

So either:

  1. my understanding is incorrect -- but I expect @jontje to weigh in in that case
  2. something is misconfigured on your IRC5 (or configured in a way we did not expect)
  3. something is misconfigured on the ROS side of your setup

I'm going to wait for @jontje to add his opinion, but I expect we should follow up on this.

jontje commented 3 years ago

Based on my understanding, EGM sessions should not time out while motions are executing.

Yes, that should be true, as long as the convergence conditions are unfulfilled, which are specified in the EGM settings by the settings.activate.cond_min_max and the settings.run.cond_time fields.

Something to test could be to decrease cond_min_max and increase cond_time.

@robberthofmanfm, did you execute EGM motions for both of YuMi's arms?

/yumi/rws/sm_addin/start_egm_joint "{}" starts EGM sessions for both of YuMi's arms by default, so if only one arm is moving and the other is standing still, then the arm that is standing still can timeout.

One way to mitigate this is to set the "settings.allow_egm_motions" for respective arm.

gavanderhoorn commented 3 years ago

@jontje wrote:

@robberthofmanfm, did you execute EGM motions for both of YuMi's arms?

IIUC, both arms were moving (https://github.com/ros-industrial/abb_robot_driver/issues/16#issuecomment-790510238):

@robberthofmanfm wrote:

Edit: with YuMi, there are two channels. Are you using both at the same time, or only one?

Both at the same time, and both go Idling... after 60s, even if both are moving. (IIRC, to be confirmed tomorrow).

Edit: confirmed: both go idling after 60s while both are moving.