Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

EGM state change error #59

Closed
lijianhualeigua opened this issue Sep 11, 2019 · 5 comments
Closed

EGM state change error #59

lijianhualeigua opened this issue Sep 11, 2019 · 5 comments
Labels
rapid Issues with the RAPID side of EGM

Comments

@lijianhualeigua
Copy link

lijianhualeigua commented Sep 11, 2019

Hi, everyone:
I always get the error " EGM state chang error", when runing the EGM in RobotStudio.
We'd greatly appreciate any help with this issue!Thank you very much!

The RAPID program in here:

MODULE TRob1Main
    ! Home position.
   ! LOCAL CONST jointtarget home := [[0, 0, 0, 0, 0, 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, 0];
    VAR JointTarget joints_target;
    PROC main()
        joints_target := CJointT();
        MoveAbsJ joints_target, v200, fine, tool0;
        WHILE TRUE DO
            ! 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
                        \SampleRate:=4
                        \MaxPosDeviation:=1000
                        \MaxSpeedDeviation:=1000.0;
                        
            ! Start the EGM communication session.
            EGMRunJoint egm_id, EGM_STOP_HOLD, \J1 \J2 \J3 \J4 \J5 \J6 \CondTime:=5;
            
            ! Release the EGM id.
            EGMReset egm_id;
        ENDWHILE
        
    ERROR
        IF ERRNO = ERR_UDPUC_COMM THEN
            TPWrite "Communication timedout";
            TRYNEXT;
        ENDIF
    ENDPROC
ENDMODULE
@gavanderhoorn
Copy link
Member

gavanderhoorn commented Sep 11, 2019

@lijianhualeigua: it's going to be a little while before we can assist you. Both @jontje and me are extremely busy the coming two weeks.

If a community member has an idea here, don't hesistate to comment.


Edit: in the meantime: did you write the RAPID side yourself, did you copy it from somewhere or did the StateMachine addin generate it for you?

@jontje
Copy link
Contributor

jontje commented Nov 25, 2019

I always get the error " EGM state chang error", when runing the EGM in RobotStudio.
We'd greatly appreciate any help with this issue!Thank you very much!

Firstly, sorry for the slow reply! Secondly, is this still an issue? It looks like it comes from one of the examples found in issue #18.

Anyway, I have been working on some improved examples (for RobotWare 6.09 and newer) and it looks something like this:

!***********************************************************
! 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_1;

!***********************************************************
!
! Main procedure
!
!   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()
    ! Register an EGM id.
    EGMReset egm_id_1;
    EGMGetId egm_id_1;
    
    ! Setup the EGM communication.
    EGMSetupUC ROB_1, egm_id_1, "default", "ROB_1", \Joint \CommTimeout:=30;
    
    ! Prepare for an EGM communication session.
    EGMActJoint egm_id_1 \MaxSpeedDeviation:=20.0;
    
    ! This example is only intended for simulation in a virtual controller.
    WHILE NOT RobOS() DO
        WaitRob \ZeroSpeed;
        MoveAbsJ home, v200, fine, tool0;
                    
        ! Start the EGM communication session.
        EGMRunJoint egm_id_1, EGM_STOP_HOLD \NoWaitCond \J1 \J2 \J3 \J4 \J5 \J6 \CondTime:=60;
        
        WaitTime 25;
        EGMStop egm_id_1, EGM_STOP_HOLD;
    ENDWHILE
    
ERROR
    IF ERRNO = ERR_UDPUC_COMM THEN
        TPWrite "Communication timedout";
        TRYNEXT;
    ENDIF
ENDPROC

I hope this might be of use although it's a bit late.

@lijianhualeigua
Copy link
Author

Great, thanks a lot. I really appreciate it.
I will to try this improved method.

@gavanderhoorn
Copy link
Member

@lijianhualeigua: have you resolved this?

Can this issue be closed?

@gavanderhoorn
Copy link
Member

Closing due to inactivity.

If this is still an issue, we can re-open.

@gavanderhoorn gavanderhoorn added the rapid Issues with the RAPID side of EGM label Feb 5, 2020
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
rapid Issues with the RAPID side of EGM
Development

No branches or pull requests

3 participants