-
Notifications
You must be signed in to change notification settings - Fork 51
Description
Hello @stephanie-eng and @gavanderhoorn,
I've noticed a potentially serious problem with the behavior of this hardware interface which is summarized in the video below. I've detailed the cause and a temporary fix i'm using. But would like to get your thoughts on what a proper fix should look like.
The problem
Say I move the ABB robot to a non-zero joint configuration before starting the EGM client on the robot. In this example, joints 1-3 are set to 30deg or 0.5235rad. You can see the console output in RobotStudio where the robot is waiting to connect to the EGM server.
I then launch the hardware_itnerface and joint_trajectory_controller following the exact command from the README but after replacing the IP address with that of my robot. You can see that as soon as the EGM server starts and registers the client, it moves the robot to all zero joint positions. This is even after I've explicitly set the initial position values to 0.5235rad of the resp state interfaces in the irb1200.ros2_control.xacro
file (bottom terminal).
abb_ros2_init_motion.mp4
The behavior is dangerous as our robot operates within an enclosure with many obstacles which may collide with it as it moves to 0 joint value configuration on startup. The expected behavior is for the hardware_interface to not move the robot to this configuration at start but instead keep the robot at the initial value specified in the ros2 control xacro.
Root cause of the problem.
The problem lies in the way the initializeMotionData that is called by this hardware interface as seen here is implemented. The implementation hardcodes motion_joint.command.position = 0.0;
. Hence, once EGM connects, it commands all the joints to 0.0 rad.
Temporary fix
As a interim solution, i'm using a fork of abb_egm_rws_managers
where I hardcode the motion_joint.command.position
values in initializeMotion()
with initial joint values that my robot starts in. In the video below, you can see that once the EGM server connects with the robot client, it does not command the robot joints to 0rad and i'm able to plan and execute motions from this initial position of the robot.
abb_ros2_custom_fix.mp4
Proper fix
Here's my proposal for a more general fix. If this sounds ok, I'm happy to open the necessary PRs.
- Get and store the
initial_values
for each joint from thehardware_interface::HardwareInfo
passed into AbbSystemHardware::on_init() - Pass these initial values to
initializeMotion()
and use the values to setmotion_joint.command.position
for each joint.
Let me know your thoughts on this approach. I can try to do this without breaking any API.
On a slightly unrelated note,
I would also like to propose not using RWS to get the RobotControllerDescription
as seen here. This works well for RWS1.0 but when interfacing with RWS2.0 on omnicore, it fails. I've resorted to manually creating the RobotControllerDescription
object as described in this comment when working with omnicore robots. I think it should be possible construct this description by parsing the HardwareInfo
. Or atleast have an option to either use RWS or parse HardwareInfo to get this information. I understand that getting this data from RWS is useful when there are external axes involved.