Professional Documents
Culture Documents
A) Teach Pendant
B) Robot point definition
C) Program
D) User interface
A) Teach Pendant
In automatic mode small changes of robot positions, speed, timing can be done by using teach
pendant´s “Auto-Menu”.
For example: If height of P_pick_up must be changed while press is in automatic mode then
follow these steps:
- select “position setup” by pressing “0” and “Enter” on teach pendant
- then an additional menu will be shown where you can change x, y and z position +/- 0.2
mm.
- if you want to change z-position deeper than select “6” and press “Enter”
- now z-position of P_pick_up is 0.2mm deeper than before.
- if you press again “Enter” than again P_pick_up will be 0.2mm deeper and so on.
- to go back to main “auto-menu” press “CLR” then “0” then “Enter”.
In “teach-mode” all robot points can be teached by using “teach pendant”
Move robot manually (robot motors are switched off) or electrically (motor is on) to
“P_pick_up”-position.
To move to position manually first switch off motors then move robot by hand to position. Do
mot use spindle to move robot because spindle could be bend slightly. To change z-position
and orientation of robot just press white “brake release”-button on top of robot housing.
To move to position electrically first switch on “motor” power. Press “safety switch” on back
of pendant and press button “Motor” then “OK” to activate motors. “Safety switch” must
always be kept half pressed when operating with teach pendant.
When motors are activated “LED” will flash and also orange light on top of
robot will flash.
Attention when robot is under power please always keep security distance !!!
Nobody is allowed to stay near to robot when under power!
Robot got 4 electrical axis or joints J1 to J4. These axis can be moved singulary -> Jog-mode
= “Joint” or can be moved in Cartesian coordinates -> Jog-mode =”World” must be selected.
When moving bigger distances switch “speed” to “high”. When getting close to end-position
change back “speed” to “low” for finer positioning.
Move to position by using J1..4 +/- keys.
-> or
Now you get several options for moving which can be selected by using the up/down-arrows.
Most useful are Motion command Jump and Go.
“Jump” will make and up-movement followed by a horizontal movement and finally a down-
movement. This behaviour will prevent collisions while moving.
“Go” will make a direct movement to selected target point. So watch for possible collisions.
After selecting “Jump” or “Go” press button “OK”.
Now select point you want to move to. For example: point 3 with label “P_throw_off”
Finally press “OK” button and keep on pressing. When motor power is on then robot will
move to selected point as long as you press “OK” and press safety switch on backside of teach
pendant.
Repeat this procedure for all points with numbers 0 to 3 to check if position is teached
correctly.
Monitoring and controlling inputs and outputs of robot controller
Press “F8” “I/O Cmd” to open menu for inputs and outputs of robot controller
Then press “F7” “Outputs”.
Output 13 of robot controller is connected with vacuum-valve for suction head of robot.
Actual status of output is “Off”. In other words valve is switch off and vacuum is off.
By pressing “F5” “On” output will change status to “On”. Now valve is actuated and vacuum
is on. Operator can adjust strength of vacuum by regulating pressure controller and can test
function of suction head for leakage.
By pressing “F6” “Off” output will change status back to “Off”.
All other outputs are not used.
B) Robot points
Totally 4 teach points are defined + 2 points which define position of press table in relation to
robot (see pictures below).
In Automatic mode robot will wait in “P_base_pos” for start-signal from press.
When start_impuls is detected then robot will move vertically down to “P_pickup”. While
moving down vacuum is switched on. When in position robot will wait pickup-time.
When timer ended then robot will make a Jump-movement to “P_place” or “P_throw_off”
depending if throw_off-condition is active.
With softkey “robot zrzucic” manual throw-off can be activated and deactivated.
After robot reached “P_place” or “P_throw_off” vacuum will be switched off, article will be
palced or thrown away. Robot will wait adjusted timing and finally move back with Jump-
movement to “P_base_pos”.
Adjust timing, speed and acceleration until robot total movment time is within allowed limits.
If robot is too slow timing-bar “pozostaly czas” will be in red colour and residual time will be
negative. Make robot movement faster until colour will change to green and residual time will
be positive. If you do not follow these steps robot will not be able to take all articles. Only
each second article will be taken!
2 P_place defines place position over fire polishing plates. Before teaching
this point check if pick up postion of “take out fire polishing” is
correctly set. When pick up arm and plate of fire polishing
machine is aligned then teach place position of robot.
3 P_throw_off defines throw off position over chute. When robot can not put
articles on fire polishing machine (for example some fault is
active or fire polishing is switched off or robot has been told to
throw off all the time) then robot will move to this position.
Because point “P_pickup” and “P_base_pos” are not fixed and are dependent of position of
sliding frame a special procedure is necessary to teach that points!
Teaching of points press must be in manual mode.
Or
See actual robot project “Irena Polen 18 7” for example and open this project for printing
program or see below for program description.
Program consists of several tasks which are running parallel (multitasking)
And functions:
1. main task
2. error and status handling task
3. communication task
4. user interface task (teach pendant)
5. coordinate transformation function
C.1. Main task: contains main program and moving instructions for robot in automatic
mode
'---------- AUTOMATIK - PROGRAM --------------------------------------------------------------------------------------------------
' Project: Irena Polen Robot Linie 1
' robot with fieldbus interface Profibus Adr. 4
' Date: 10.01.2015
' Author: M. Stark
' Company: WALTEC Germany
'----------------------------------------------------------------------------------------------------------------------------------
Global Preserve Real PickUpTime Defines parameters which are valid all over the program
Global Preserve Real GiveOffTime (global) and are always stored inside SRAM memory of robot
Global Preserve Real GiveOffTime2 (preserve) and hence cannot be deleted (after power fail)
Global Preserve Integer Vel, LimZAxis, Acc, Dec
Global Preserve Real Z_up, Z_down, Z_down_lim
Global Preserve Real delta_X, delta_Y, delta_Z, delta_Xr, delta_Yr
Global Real CycleTime Defines parameters which are valid all over the program
(global) and are not stored inside SRAM memory (battery
buffered) of robot and hence will be deleted after power fail
Function main ' main function: start of automatic program which is selected by fieldbus inputs: SEL_PROG_1=SEL_PROG_2=SEL_PROG_4=false
Xqt main_UserInterface ' multitasking: starts user interface task Touch Pendant TP
Xqt main_Error_and_Status ' multitasking: starts error handling and status task
Xqt main_Communication ' multitasking: Sending and receiving data via Profibus
TLSet 1, XY(234, 0, 0, 0)
' calculation of rotation shift of coordinate systems of robot and sliding frame
alpha = Atan(Abs(CX(P_slidingframe1) - CX(P_slidingframe2)) / Abs(CY(P_slidingframe1) - CY(P_slidingframe2)))
Print "alpha =", alpha ' angle in rad (alpha apporx. 20° according to construction plan)
' OnErr GoTo errHandler ' automatic error handling routine -> stops robot !!
LimZ LimZAxis ' height limiting -400mm..0mm -> value can be changed also in automatic mode (JUMP movement)
Accel Acc, Dec ' acceleration 0..120% -> value can be changed also in automatic mode
Speed Vel ' velocity 0..100% -> value can be changed also in automatic mode
' robot is waiting in base_position (throw off pos.) and suction head is pointing upwards
If Sw(I_Preselection) = 0 And In_Home_Pos = 0 Then ' if robot is not selected or compressed air is missing then robot will move to base position
Speed 5
Go P_base_pos +X(delta_Xr) +Y(delta_Yr) +Z(delta_Z)
In_Home_Pos = InPos
On Q_enable_table
On Q_EnableTable
Off Q_vacuum
Wait 2
EndIf
If Sw(I_Preselection) = 0 Then
GoTo End
EndIf
If Sw(I_Home) = 0 Or In_Home_Pos Then GoTo Start ' if robot has to move to base_position and is not already there then he moves home
Speed 5 ' else it will wait for starting signal of press.
Go P_base_pos +X(delta_Xr) +Y(delta_Yr) +Z(delta_Z)
In_Home_Pos = InPos
On Q_enable_table
On Q_EnableTable
Wait 2
Off Q_vacuum
Wait 2
GoTo End
Start: If Sw(I_Start) = 0 Then GoTo End ' waiting for start impulse in automatic mode
LimZ LimZAxis ' height limiting -400mm..0mm -> value can be changed also in automatic mode (JUMP movement)
Accel Acc, Dec ' acceleration 0..120% -> value can be changed also in automatic mode
Speed Vel ' velocity 0..100% -> value can be changed also in automatic mode
' read differential position of sliding frame and convert it to robot coordinate system
Call main_Koord_Transformation(alpha)
‘ Till Sw(I_Start) = 0 ' stop-condition for next move of robot (already started move will be stopped if condition is not true -> prevention of collisions)
' Input I_Start has to be true until pick up is finished else robot will quit pick up and move to base position
' PTP movement up to tracked pick_up position - Z(Z_up) with suction head turned upwards .. while moving vacuum is switched on ....
In_Home_Pos = False
Go P_pick_up +X(delta_Xr) +Y(delta_Yr) +Z(delta_Z) -Z(Z_up) Till ! D20; D10; On Q_vacuum; D10; Off Q_enable_table !
Wait PickUpTime ' waiting PickUpTime -> value can be changed also in automatic mode
If Sw(I_Throw_Off) Then GoTo ThrowOff
' If input I_Throw_Off is true or I_Start is false then move to throw_off postion (base_position)
GoTo End_2
ThrowOff:
On Q_EnableTableFPM ' enable table turning of fpm
' PTP movement to base position and throw off of article -> point can be changed also in automatic mode
Jump P_throw_off ! D10; On Q_enable_table !
On Q_blow_out, 0.1, 0
Off Q_vacuum ' switch off vacuum
Wait GiveOffTime2 ' wait give_off time 2 -> value can be changed also in automatic mode
Jump P_base_pos +X(delta_Xr) +Y(delta_Yr) +Z(delta_Z) C0 LimZ LimZAxis
End_2:
On Q_Acknowledge, 0.25 ' acknowledge signal for press for cycle time measurement
End:
CycleTime = Tmr(0) ' robot cycle time measurement
Print CycleTime
Resume main_Communication ' to avoid error 2200 (not tested)
Loop
Exit Function
errHandler: ' error handling -> each error will stop robot !!! (deactivate if necessary)
Select Err
Case F_ParNotValid
Print "Error: Parameter not valid ! "
EResume Next
Case F_MonitoringWaterCooling
Print "Error: Monitoring water cooling ! "
EResume Next
Case F_MonitoringAir
Print "Error: Monitoring compressed air ! "
EResume Next
Case F_MonitoringVacuum
Print "Error: Monitoring vacuum ! "
EResume Next
Send
Fend
C.2. error and status task
Function main_Error_and_Status ' multitasking: starts error handling and status task
Do
If Oport(Q_Error) = 1 Or Oport(Q_SError) = 1 Then ' error active
Off Q_enable_table
' when robot is in fault state switch off enabling of both tables (press and fpm)
Off Q_EnableTableFPM '
Off Q_vacuum
' switch off vacuum
If Not (Oport(Q_Ready) = 1 Or Oport(Q_Running) = 1) Then ' if none of these bits is active then controller is switched off
EndIf
CY(P_pick_up) = InReal(I_Par_Data)
CZ(P_pick_up) = InReal(I_Par_Data)
CU(P_pick_up) = InReal(I_Par_Data)
CX(P_place) = InReal(I_Par_Data)
CY(P_place) = InReal(I_Par_Data)
CZ(P_place) = InReal(I_Par_Data)
CU(P_place) = InReal(I_Par_Data)
CX(P_base_pos) = InReal(I_Par_Data)
CY(P_base_pos) = InReal(I_Par_Data)
CZ(P_base_pos) = InReal(I_Par_Data)
CU(P_base_pos) = InReal(I_Par_Data)
Default
EndIf
Loop
Fend
C.4. User interface task: contains program for interacting with user and display text
and values on teach pendant
Only an excerpt of the whole code of this task is shown and commented because the rest
of the code is very similar.
To display information and to read keys on the teach pendant there are two commands
available in SPEL programming language.
Print #24,”….” will write information on the display of teach pendant and
Input #24,a$ will wait for user interaction (pressing of keys and entering this information).
Do
Cls #24 ‘ clear screen of teach pendant
Print #24, "- WALTEC Robot -- Auto-Menu -----" 'port-number #24 defines printing to Touch Pendant display
Print #24, "1= position setup"
Print #24, "2= speed setup"
Print #24, "3= timing setup"
Print #24, "4= display actual values"
Print #24, "5= save positions"
Print #24, "”
Print #24, "-------- actual values ----------- "
Print #24, "t_cycle=", CycleTime, " s" ‘ now menu is printed and …
…….
C.5. coordinate transformation
Function main_Koord_Transformation(Winkel As Real)
' reads relativ positions of sliding frame, checks for limits and transforms coordinates system of frame to robot
' if press is moving on sliding frame robot will track pick_up position