본문 바로가기

장난감/KUKA.KRC

설정 파일 및 파일 설명

설정 파일 및 파일 설명


c:\krc\roboter\config\user\common\EthernetKRL\

오토매틱익스터널  핀 정보가 들어있음

KRC\steu\Mada\$machine.dat


사용자 변수등을 입력할 수 있다(글로벌 변수가 모두 선언됨)

KRC\R1\System\$config.dat


PLC처럼 사용할 수 있는 모듈(명령어 해석기가 실행되면 이것도 항상 실행중이다)

KRC\R1\System\sps.sub


외부자동모드일때 기본으로 지정되어있는 실행파일(외부자동모드를 작성한다면 이 파일을 먼저 참고하길)

KRC\R1\cell.src


설정관련 내용이 들어잇음(외부자동모드의 Chk_movena 를 False 해야할때 사용한다)

KRC\steu\Mada\$option.dat


SPS.SUB is run in the background by the “Submit Interpreter”. It is run in parallel to the main program. Some restrictions apply and certain variables are write protected. These are some bits and pieces that may be useful.

SPS.SUB is responsible for starting CELL.SRC when in automatic external mode; CELL.SRC, in turn, reads the I/O lines and calls the correct program. However, with some modifications, CELL.SRC is no longer needed. We can start our FRI control program directly.

Confirming Messages: This is a snippet for confirming messages:

INT M
DECL STOPMESS MLD
IF $STOPMESS AND $EXT THEN      ;If there is a stop message in auto external mode
   M=MBX_REC($STOPMB_ID,MLD)    ;Read current state in MLD
   IF M==0 THEN                 ;Check if we are allowed to confirm
      IF ((MLD.GRO==2) AND (MLD.STATE==1)) THEN
         CONFIRM MLD.CONFNO     ;Confirm this message
       ENDIF
   ENDIF
ENDIF

When omitting the check MLD.STATE==1 then almost every message gets confirmed. In this application this makes sense after the ON button was pressed.

Controlling the program state: By writing commands to the $CMD stream one can start, stop or reset KRL programs:

CWRITE($CMD,STAT,MODE,"RUN /R1/FRI_CONTROL()")
CWRITE($CMD,STAT,MODE,"STOP 1")
CWRITE($CMD,STAT,MODE,"RESET 1")

Some variables:

  • $MODE_OP: One of #EX#AUT#T1#T2. The current robot mode.
  • $EXT: robot mode is “Automatic external”. This is a bit more compact than ($MODE_OP==#EX). Similar variables are $T1$T2 and $AUT.
  • $PRO_STATE1:
    • #P_RESET: The program was reset
    • #P_FREE: No program selected
    • #P_ACTIVE: Program is running
    • #P_STOP: Program is stopped
  • $PERI_RDY: Drives are ready
  • $STOPMESS: A stop message is being displayed
  • $PRO_ACT: A program is running

The following variable is not supported with FRI 1.0.0, but has been used by others:

  • $FRISTATE: Can be #MON or #CMD

IO-lines on the Kuka-C2 controllers

The KRC that ships with the lightweight arms has no physical input or output lines. You have to attach some IO-module using an industrial bus. However, there is a (pretty hackish) way to get some slow IO-lines with only a few wires and some code:

From KRL it is possible to control the serial port COM3 and send (and receive) some command characters (using the CWRITE and CREAD commands). Then you connect COM3 to COM2 (which is controlled by the windows side) These commands are interpreted by a windows program which runs on the KRC in the background (find the source here). This program can set the handshake pins on the serial port or control the parallel port. See the wiring diagram below:

             ______________________
         ___/________________      \
       _/___|________________\_    |
      / |   |                | \   |
      | |   |                | |   |
      | |  _|_____           | |   |
   RxD| | / |     \       RxD| |   |
     TxD| | +---\ |         TxD|   |GND
  ____|_|_|_|__ | |      ____|_|___|__
  \ 1 2 3 4 5 / | |      \ 1 2 3 4 5 /
   \ 6 7 8 9 /  | |       \ 6 7 8 9 /
    ---------   | |        ---------
       COM2     | |          COM3
                | |
             GND| |DTR
                | |

               OUTPUT

The serial port should provide two outputs and two inputs (+-12V). The parallel port has some more…

Other things to know

  1. The second joint (J2/A2) is at 90 degrees when it is completely stretched. This is due to some convention of Kuka. However, the FRI interface does not have this offset. With FRI, all joint limits are symmetric (i.e. J2 is zero when stretched). This suits us well, we would have removed this offset in our driver, anyway.
  2. When the variance of the estimated force ($TORQUE_TCP_EST) is bigger than around 10-15, then the arm is in a singular pose and the estimated forces should not be trusted.
  3. The message “483 - LR - Computation of Cartesian Deviation impossible” can be overcome by switching back to position control. This requirement is reportedly gone in the newest version of FRI.

Glossary