RobotStudio event

Problem with DeviceNet communication

Hello Colleagues,

I am working on connecting externa device (electrical griiper festo) with robot controller IRC5 by using deviceNet. I have some problems, because after base configuration, external controller SFC-DC shows me that devicenet is in operational mode. But, if I want to communicate by RAPID code, prgram has problems with instruction "open". Please find files like EDS file and backup my station in attachment.
I would be grateful for your help.


Best regards
Pawel

Comments

  • Hello,
    If i look at your code
    you do the command : Open "/FCI1:/board328", io_device \Bin;
    but you don't have declared what is board328 i think, you have declared in your IO.SYS a board "IED_device_unit"
    #
    EIO_UNIT:

          -Name "IED_device_unit" -UnitType "Device_IED_Type" -Bus "DeviceNet1"\
          -UnitLabel "9" -TrustLevel 2 -RegainCommunicationReset  -DN_Address 3

    so maybe you should try to do Open "/FCI1:/IED_device_unit", io_device \Bin;
    It's is only a quick thought, because i have never worked this way with devicenet

  • Hello,
    I tried to modify program, but still I have some problems. If I try to send a message in order to get status Device controle (param10 in EDS file), I obtain nothing.
    Example code:
    MODULE Module1
        CONST robtarget home:=[[511.36,-7.11,714.35],[0.709925,0.0106723,0.704196,0.000937047],[-1,-1,0,1],[9E+09,9E+09,9E+09,9E+09,9E+09,9E+09]];
        CONST robtarget target1:=[[511,-7.11,400],[0.709925,0.0106723,0.704196,0.000937047],[-1,-1,0,1],[9E+09,9E+09,9E+09,9E+09,9E+09,9E+09]];
     
        CONST robtarget board1home := [[223.04,-154.57,-159.66],[0.613404,-0.560875,-0.422732,-0.36118],[-1,0,-3,0],[9E+09,9E+09,9E+09,9E+09,9E+09,9E+09]];
        CONST robtarget Target_10:=[[476.377532198,75.790964764,329.998886795],[0.006634996,0.000000077,0.999977988,-0.000000033],[0,-1,0,0],[9E9,9E9,9E9,9E9,9E9,9E9]];
        CONST robtarget Target_20:=[[476.377564349,-79.852510653,329.999196286],[0.006635425,-0.000000054,0.999977985,-0.000000177],[-1,0,-1,0],[9E9,9E9,9E9,9E9,9E9,9E9]];
        CONST robtarget Target_30:=[[476.377648812,-1.144353486,329.999431058],[0.006635615,-0.000000149,0.999977984,-0.000000072],[-1,0,-1,0],[9E9,9E9,9E9,9E9,9E9,9E9]];
        VAR num dlugosc;
        VAR iodev io_device;
        VAR rawbytes raw_data_out;
        VAR rawbytes raw_data_in;
        VAR num input := 46;
        VAR string return_status;
        VAR string return_status_in;
        VAR string wynik := "0";
        VAR byte bit := 122;
        CONST robtarget Target_50:=[[476.377617427,-1.144352136,470.80365528],[0.006635644,-0.000000406,0.999977984,-0.000000065],[-1,0,-1,0],[9E9,9E9,9E9,9E9,9E9,9E9]];
        PROC main()
            MoveJ home,v1000,z100,tool0\WObj:=wobj0;
            devicenet;
            MoveJ target1,v1000,z100,tool0\WObj:=wobj0;
            MoveJ home,v1000,z100,tool0\WObj:=wobj0;
            Stop;
        ENDPROC
        
        PROC devicenet()
            wynik := ByteToStr(bit);
            Close io_device;
            ClearRawBytes raw_data_out;
            PackDNHeader "0E", "6,20 64 24 01 30 0E,207D,00", raw_data_out;
            !    I think here is the main problem - how to correct define PackDNHeader based on EDS file?
            PackRawBytes input,raw_data_out,(RawBytesLen(raw_data_out)+1) \INTX := UDINT;
            dlugosc :=RawBytesLen(raw_data_out)+1;
            Open "/FCI1:/IED_device_unit", io_device \Bin;
            !trzeba znalezc ID w plik EDS urzadzenia IO, aby otworzyc z nim polaczenie
            WriteRawBytes io_device,raw_data_out;
            ReadRawBytes io_device,raw_data_in\Time:=1;
            Close io_device;
            UnpackRawBytes raw_data_out,9,return_status \ASCII:=46;
            UnpackRawBytes raw_data_in,9,return_status_in \ASCII:=46;
        ENDPROC
        
    ENDMODULE

    If you have some suggestions, please let me know.

  • What if you use this

    PackDNHeader "16","20 64 24 01 30 03,1,C6,1",raw_data_out;
    Per Svensson
    Robotics and Vision Specialist
    Consat Engineering
  • Unfortunately it doesn't work. If I use: PackDNHeader "16","6,20 64 24 01 30 03,1,C6,1",raw_data_out; prgram works but I have no response from slave controller.
    Should I create fieldbus commands and field bus command types?

    Do you have other suggestions how to solve the problem?
  • I wonder if I properly set up PackDNHeader. I should send to slave controller 8 bytes acc. to SFC-DC Festo documentation.  How to correct define message?
  • Hi,

    I collect here some lines from my working program. Notice this is just sample and not complitetly working PROC, but this is more or less what works for me. You need to find your path from EDS file and add data into rawbyte if needed to send some data.

    ------------------------------------------

     ! Constants
     CONST string DNET_GET_ATTR_SINGLE := "0E";
     ! paths get from EDS file
     CONST string DNET_PATH := "6,20 64 24 02 30 01,C4,4";
     CONST num DNET_READ_WAIT_TIME := 1;


     ! Variables
     VAR iodev devDNet;
     VAR string strDNetService;
     VAR rawbytes rbWrite;
     VAR rawbytes rbRead;
     VAR string strPath;
     VAR string strData;
     VAR string strDeviceName;

    PROC foo()
      
      strDNetService := DNET_GET_ATTR_SINGLE;
      strPath := DNET_PATH;
      strDeviceName := "YOUR_DEVICE_NAME";

      ! clears all rawbytes variables/data.  
      ClearRawBytes rbWrite;
      ClearRawBytes rbRead;

      ! If needed add Data to message
      ! e.g add string data to rawbyte variable
      strData := "ASCII string here";
      PackRawBytes strData, rbWrite, (RawBytesLen(rbWrite)+1) \ASCII; 

      ! Set DeviceNet header
      PackDNHeader strDNetService, strPath, rbWrite;


       ! Open FCI device
       Open "/FCI1:" \File:=strDeviceName, devDNet \Bin;
       
       ! Write the contents of rawbyte to devDNet
       WriteRawBytes devDNet, rbWrite \NoOfBytes := RawBytesLen(rbWrite);
       
       ! Read the answer from devDNet
       ReadRawBytes devDNet, rbRead \Time := DNET_READ_WAIT_TIME;
       
       ! Close device
       Close devDNet;

    ENDPROC

    -------------------------------------


    Regards,

    Mika

  • Thank You Mika.
    I have now communication between controllers IRC5 and Festo SFC-DC. I can get values from festo controller.
    But I have one more question: What type of procedure should we use in order to send command as SET type? Path should be improved? I think more parameters we need to send.

    CONST string DNET_SET_ATTR_SINGLE := "10";
     ! paths set LCD contrast from EDS file
    CONST string DNET_PATH := "6,20 64 24 01 30 10,C6,1";

    I can for example set up LCD contrast by set values between 0-63. How to do it?

    Thank you very much for help.
  • Hi,

    For SET use same procedure as GET with comments following....

    - Path is same. Path is just as pointer to the register in your device and you should see from your device doc if register support GET, SET or both.

    - When making the header use SET service "10" instead of GET "0E"

    - Add your data with PackRawBytes into the message, see my sample how to add ASCII data. Remember different data types need different parameters.


    Mika

  • Thanks a lot for help.
    Program works very good after changing lines in code:


     ! Set DeviceNet header
     PackDNHeader strDNetService, strPath, rbWrite;
     PackRawBytes strData, rbWrite, (RawBytesLen(rbWrite)+1) \ASCII; 

    This topic we can close.