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
92 stars 52 forks source link

RobotWare 6.13 EGM UdpUc error #132

Open Luc90 opened 2 years ago

Luc90 commented 2 years ago

Hello,

I work with the Yumi and EGM. I upgraded the RobotWare version from 6.12 to 6.13. My Rapid code worked when I was using version 6.12 but with version 6.13, when I run the Rapid code I get the following two errors:

I also updated the RobotWare to version 6.13 of the ABB1200 in our lab and tried to run the same Rapid EGM code. This works on the ABB1200 with RobotWare version 6.13.

I tried with the Yumi by simulating RobotWare versions 6.11 and 6.12 and it works.

Do you know why I get these errors with RobotWare 6.13 on the Yumi ?

My Rapid code is

`MODULE TRob1Main

!***********************************************************
! Program data
!***********************************************************
! Home position.
 LOCAL CONST jointtarget home:=[[0,-130,30,0,40,0],[135,9E+09,9E+09,9E+09,9E+09,9E+09]];

! Identifier for the EGM correction.
LOCAL VAR egmident egm_id;

! Limits for convergance.
LOCAL VAR egm_minmax egm_condition := [-0.1, 0.1];

!***********************************************************
!
! Procedure main
!
!   This RAPID code exemplify how to run EGM joint position
!   motions.
!
!   Note: Update the UCDevice "ROB_1" with correct
!         values for the remote address and port
!         (i.e. to the EGM server).
!
!         Update via RobotStudio:
!         Controller tab -> Configuration ->
!         Communication -> Transmission Protocol
!
!***********************************************************
PROC main()

    MoveAbsJ home, v100, fine, tool0;

    WHILE TRUE DO

        ! Register an EGM id.
        EGMGetId egm_id;

        ! Setup the EGM communication.
        EGMSetupUC rob_L, egm_id, "default", "ROB_1", \Joint;

        ! Prepare for an EGM communication session.
        EGMActJoint egm_id
                    \J1:=egm_condition
                    \J2:=egm_condition
                    \J3:=egm_condition
                    \J4:=egm_condition
                    \J5:=egm_condition
                    \J6:=egm_condition
                    \J7:=egm_condition
                    \MaxSpeedDeviation:=180.0;

        ! Start the EGM communication session.
        EGMRunJoint egm_id, EGM_STOP_HOLD\J1\J2\J3\J4\J5\J6\J7\CondTime:=5\RampOutTime:=1;

        ! Release the EGM id.
        EGMReset egm_id;

        WaitTime 5;
    ENDWHILE

ERROR
    IF ERRNO = ERR_UDPUC_COMM THEN
        TPWrite "Communication timedout";
        TRYNEXT;
    ENDIF
ENDPROC

ENDMODULE`

gavanderhoorn commented 2 years ago

I would check whether the remote IP setting of the UdpUc device is still correct.

Luc90 commented 2 years ago

I have checked and the remote IP setting is correct.

madelinegannon commented 2 years ago

I experienced this as well after an upgrade. I was able to receive the initial message back from the robots, indicating a successful connection, but then was sent the timeout error. I believe there was a change to the EGM protobuf in 6.13 (in looking through the RobotWare changelogs). I ended up reverting back to 6.11

gavanderhoorn commented 2 years ago

Thanks for reporting.

Could you perhaps quote the relevant part of the changelog you mention?

madelinegannon commented 2 years ago

Revision E of the EGM Applications Manual (Page 8) mentions that 2 new fields were added to the protocol message. My guess is that if you're using an emg.pb.h built for 6.XX, that the new protobuf message format is not backwards compatible. That's my best guess...

gavanderhoorn commented 2 years ago

I'm somewhat confused.

You mention RW6, but the application manual you link is for RW7.

enricovillagrossi commented 2 years ago

Hi all,

we are also dealing with the "41822, No data from the UdpUc device" we are using RobotWare 6.12. In our case, EGM is working fine, but sometimes we get the error 41822 and need to restart the EGM. Looking at the ABB Actions (see the attached image), we are in case 3. We can improve the \CommTimeout, but 1 second of timeout seems reasonable. I noticed that the error happens when the PC that hosts the abb_robot_driver is dealing with ros_control activities, which can overload the system. My guess is when the host PC of the EGM server has somehow overloaded, the communication with the robot controller is slowed down, and the robot goes into a timeout. Does anyone notice the same error? I'll try to keep the abb_robot_driver under a separete PC.

Event_Message_41822

gavanderhoorn commented 2 years ago

I'll try to keep the abb_robot_driver under a separete PC.

It could be abb_robot_driver's threads are starved, leading to the timeout.

For abb_robot_driver specifically, you could perhaps see whether installing an PREEMPT_RT kernel and then using chrt (with suitable parameters (something like --fifo -p 99 as a first test) and run by a user with the required permissions) helps mitigate this.

If your ros_control controller is taking too long, changing priorities like this likely won't help, but for other 'random' scheduling events or other thread-starvation out of the sphere of influence of abb_robot_driver, it could help.


Edit: you should be able to use chrt as a launch-prefix command, if using ROS 1 .launch files.

gavanderhoorn commented 2 years ago

Any luck @enricovillagrossi?

enricovillagrossi commented 2 years ago

We didn't try yet, we had to fix the problem quickly, we moved the abb_robot_driver on a dedicated PC, and the problem disappeared. I'll keep you informed once we will try the PREEMPT_RT kernel.

Working-Zhang commented 1 year ago

The version of abb IRB2600's robotware is 6.06,Can i update the robotware version to 6.07.01 to use this library?

gavanderhoorn commented 1 year ago

@zp666-hash-beep: for future questions: please start a thread on the Discussion forum.

Having written that:

Can i update the robotware version to 6.07.01 [..] ?

we can not answer this question for you.

Only you can decide whether you can update your controller, as we can't know whether you have other constraints and/or requirements which would prevent that.

If you don't use the controller for anything else, then the answer is most likely yes.

Working-Zhang commented 1 year ago

@gavanderhoorn Thanks for your answer.

gavanderhoorn commented 1 year ago

Off-topic here, but:

I get the error "41830 Error sending EGM UdpUc message" and in the ROS it shows "Not connected to robot" as follows.

the screenshot shows a configured "EGM port" of 65535. It's very likely this is your problem.

xiaopocheyituijiuzou commented 1 year ago

@Luc90 Hello,

I am working with a physical ABB IRB1600 and EGM to connect them with moveit2 recently. The Robotware version of the physical IRB1600 is 6.14.00.01. The Rapid code worked when I simulated the connection through whether Robotstudio 6.08 or Robotstudio 2023.1 with the Robotware version 6.08 and 6.14.00.01 verified correctly. When I ran the same code I also got the followig two errors:

Here I wonder whether the Robotware version influnces the EGM connection. And how have you overcome your bug mentioned on Feb 11, 2022. Did the Robotware version trully affect?

PS:

Here is my RAPID for EGM connection: `MODULE TRob1Main !====================================================================================================== ! Copyright (c) 2018, ABB Schweiz AG ! All rights reserved. ! ! Redistribution and use in source and binary forms, with ! or without modification, are permitted provided that ! the following conditions are met: ! ! Redistributions of source code must retain the ! above copyright notice, this list of conditions ! and the following disclaimer. ! Redistributions in binary form must reproduce the ! above copyright notice, this list of conditions ! and the following disclaimer in the documentation ! and/or other materials provided with the ! distribution. ! * Neither the name of ABB nor the names of its ! contributors may be used to endorse or promote ! products derived from this software without ! specific prior wrSitten permission. ! ! THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" ! AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE ! IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ! ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE ! LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL ! DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR ! SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER ! CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, ! OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF ! THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. !======================================================================================================

!***********************************************************
! Program data
!***********************************************************
! Home position.
LOCAL CONST jointtarget home := [[0, 0, 0, 0, 30, 0], [9E9, 9E9, 9E9, 9E9, 9E9, 9E9]];

! Identifier for the EGM correction.
LOCAL VAR egmident egm_id;

! Limits for convergance.
LOCAL VAR egm_minmax egm_condition := [-0.1, 0.1];

!***********************************************************
!
! Procedure main
!
!   This RAPID code exemplify how to run EGM joint position
!   motions.
!
!   Note: Update the UCDevice "ROB_1" with correct
!         values for the remote address and port
!         (i.e. to the EGM server).
!
!         Update via RobotStudio:
!         Controller tab -> Configuration ->
!         Communication -> Transmission Protocol
!
!***********************************************************
PROC main()
    MoveAbsJ home, v200, fine, tool0;

    ! Register an EGM id.
    EGMGetId egm_id;

    ! Setup the EGM communication.
    EGMSetupUC ROB_1, egm_id, "default", "ROB_1", \Joint;

    ! Prepare for an EGM communication session.
    EGMActJoint egm_id
                \J1:=egm_condition
                \J2:=egm_condition
                \J3:=egm_condition
                \J4:=egm_condition
                \J5:=egm_condition
                \J6:=egm_condition
                \MaxSpeedDeviation:=20.0;
    WHILE TRUE DO
        ! Start the EGM communication session.
        EGMRunJoint egm_id, EGM_STOP_HOLD, \J1 \J2 \J3 \J4 \J5 \J6 \CondTime:=5 \RampOutTime:=5;
    ENDWHILE
    ! Release the EGM id.
    EGMReset egm_id;

ERROR
    IF ERRNO = ERR_UDPUC_COMM THEN
        TPWrite "Communication timedout";
        TRYNEXT;
    ENDIF
ENDPROC

ENDMODULE`

And my reference url is: https://github.com/PickNikRobotics/abb_ros2/blob/rolling/docs/README.md

I am sincerely looking forward to your precious advice.

enricovillagrossi commented 1 year ago

Hi,

when you add the new UdpUc transmission protocol which IP address have you used? The IP must be the one of the PC running the EGM server, so your external PC.

xiaopocheyituijiuzou commented 1 year ago

@enricovillagrossi

Thanks for your comment. I am trying to connect the physical IRB1600 (one click connected to PC1) to the Moveit2 operated on PC2 (also external PC). So the new UdpUc transmission protocol IP address is that of the PC2 (also external PC ). This worked when I simulated using a simulated IRB1600 but failed when I changed to a physical one. https://github.com/PickNikRobotics/abb_ros2/blob/rolling/docs/README.md

图片

The PC1 IP address is set when I run the ros2 launch file on the PC2 ros2 launch abb_bringup abb_control.launch.py description_package:=abb_irb1600_support description_file:=irb1600_10_12.xacro launch_rviz:=false moveit_config_package:=abb_irb1600_10_12_moveit_config use_fake_hardware:=false rws_ip:=10.196.140.54 So I wonder whether the Robotware version matters.

Thanks for your precious comment again and may you happy day.