last revision 2021.01.05
ROBOFORTH II v16/17 |
---|
This glossary contains all the words in ROBOFORTH which are meaningful to the user.
FORTH kernel words are not included here; see the controller manual.
This entire glossary and RoboForth words are copyright D.Sands.
(adr) is a 16-bit unsigned integer (memory address)
(Num) is any positive integer.
(Val) is any value, either a positive or negative number or a constant.
(Pos) A position by name or by (num) LINE.
(name) A word name only.
(filename) A file name in the computer.
NOTE: A variable leaves its value on the stack only by use of the @ sign meaning 'fetch'. To see its contents enter:
(variable name) ?
To change its contents enter:-
(value) (name) !
where ! is the FORTH word meaning 'store'.
A constant leaves its value on the stack without the use of the @ sign. To see its value enter the constant's name followed by a period which is shortform for print.
(constant's name) .
To change its contents enter
(value) ' (name) !
where ' is the FORTH word 'tick' and ! is the FORTH word 'store'. The single quote ' means find this word in the dictionary
A tick word e.g. 'NEAR or 'LEARN implies that there is a dictionary search involved.
A question word e.g. ?STOP or ?TERMINAL implies that the word is a query, testing some hardware or software entity and in some but not all cases leaving a true or false on the stack.
For further information on each of these ROBOFORTH words, simply click on the word concerned. To subsequently return to this glossary, click the "back" button at the top of the screen.
A/
(num) ABORT - aborts leaving (num) in the variable ERR
ABSOLUTE - sets all joints to absolute movements.
ACCEL - a variable that controls acceleration, typical values from 500 to 4000
ADD - usage (adr1) (adr2) ADD - adds two coordinates together, leaving the result in an address which is left on the stack.
ADJUST - adjusts down SPEED to prevent the "too tight" error.
AL - Add to All - takes 5 or 6 values from the stack into the Cartesian variables and adds those values into every line of the currently selected route.
ALL - selects all joints for commands like MOVE, GLOBAL.
ALIGN - sets mode in which the wrist roll will adjust to the same angle to the waist whenever the waist moves in Cartesian mode, provided the wrist is vertical (plus or minus 90.0 deg.). R19: Align mode keeps the hand at the same angle to the waist as the waist moves in Cartesian mode.
AGAIN - a word to 'LEARN onto the end of a ROUTE to repeat the ROUTE indefinitely but only in SEGMENTED mode. Stops with escape key or soft stop button.
APPROACH (place-name) - sets the approach coordinates of a PLACE.
(pos) ASSUME - changes coordinates of WHERE to given position without moving robot e.g. 5 LINE ASSUME, NEST ASSUME etc.
AUTO (word) sets (word) to be executed on power-up (or reset)
AXES extracts the Cartesian coordinates from the address on the stack (into X Y Z PITCH W TOOL-LENGTH YAW ROLL as appropriate)
#AXES a user variable in the parameter file with the number of axes your robot has.
B/
BEEP - beeps the computer
BLUETOOTH - switches attention to the second serial port
(port-address) (bit-number) BIT? - returns a true if the given input bit on an input port is true, otherwise zero. example: PB 5 BIT? IF etc.
(bit-number) BIT - converts a bit number into a numeric value.
C/
CALCHECK - drives all joints to their datum positions and checks the position counts against the values in LIMITS. If the errors exceed a tolerance the robot stops and the error is reported.
CALIBRATE - drives all joints to their datum positions and corrects the position counts to the values in LIMITS
CALSEQ - an array for R15, R19, R12-6, R17-6 determining the order in which axes calibrate.
CARTASSUME - same as AXES
CARTEACH - same as JOG
CARTESIAN - selects cartesian mode i.e positioning to x-y-z coordinates.
CF - Cartesian Fetch, sends back 5 or 6 values of the Cartesian position.
CG - Cartesian Get - takes 5 or 6 values from the stack into the Cartesian variables. Send the 5 or 6 values in reverse order ending with X, then CG.
CM - Cartesian Move - takes 5 or 6 values from the stack into the Cartesian variables and moves the robot to that position. Send the 5 or 6 values starting axis 5 or 6 ending with X, then CM.
CARTWHERE - displays cartesian coordinates even if in joint mode. These coordinates may not be valid - update with COMPUTE.
#CARTS - the number of Cartesian axes. Usually the same as #AXES.
CHECK - similar to CALIBRATE but does not correct any errors.
CL - learns data in cartesian coordinates though system may be in joint mode.
CLRDSP - clears DSP busy flag (see ?RUN)
(object) COLLECT - sends the arm to the location of the object and GETs it (see GET). No longer available in V17
COMPUTE - computes new values for the cartesian variables X,Y,Z, W, PITCH from the motor counts.
CONTINUOUS - puts system into continuous mode i.e. will run a ROUTE without stopping at each line.
CONVERT - converts the Cartesian coordinates of a route to joint coordinates. The original Cartesian coordinates will still be visible in RobWin.
CREEP-FACTOR - variable determining speed joint moves in TEACH
CRITERION - a vector variable for determining the event which ends a search.
CRUN - a continuous run but does not depend on CONTINUOUS mode and CPU does not wait for DSP to finish. To stop the robot execute STOP - see also ?RUN
D/
DATUM - sends selected joint to home position
DE-ENERGISE or DE-ENERGIZE - removes power (and holding torque) from all joints.
(num) DELETE or (num) LINE DELETE - removes the specified line from the currently active ROUTE and shifts the other line down to close the gap. LINE may be omitted. Do not use with PLACEs.
DISABLE - disable interrupts.
DOWN - moves robot to target position of a GRID or ROW, the line number left in LINE# by NEAR
DRY - sets a mode to test a CONTINUOUS ROUTE for errors without running the robot, syntax: DRY RUN. To actually run enter CONTINUOUS. SEGMENTED also cancels DRY mode.
DRUN - a dry run without changing mode
DSPASSUME - assumes position of last move made by the DSP.
DSPCHANS - the number of axes passed to/from the DSP (always 6).
DSPMOVE - similar to MOVE but motion is controlled by the DSP. Control returns to the CPU before robot stops moving. The robot will not stop with the stop button. Enter STOP to stop the robot.
DSPRDY - waits for DSP to finish
DSPSMOOTH - same as XGOTO in SMOOTH mode i.e. motion is controlled by the DSP but control returns to the CPU before robot stops moving. The robot will not stop with the stop button. Enter STOP to stop the robot.
DSPVEC - variable for vectored execution - any word CFA in this variable will be executed while a CONTINUOUS path ROUTE is running. The word will be executed many times i.e. treat it like polling. If the word is to be executed only once use a flag.
E/
ENC1 - reads value from encoder 1 register onto stack (see LATCH)
ENC2 to ENC6 - similar to ENC1 but for encoders 2 to 6
ENCABORT - word which aborts with encoder-stepper mismatch message and ERR=2.
ENCASSUME - changes the motor counts to those indicated by the encoders (copies line 3 to line 1 of WHERE
ENCLEARN - learns joint coordinates from the encoder counts.
ENCCHECK - this checks the encoder count against the stepper count, using the conversion factors in ENCRATIOS.
ENCERR? - leaves true (non-zero) on stack if there is an encoder error on any axis which exceeds the amount in the corresponding element of ENCTOLS
ENCOFF - disables encoders but leaves them displayed in WHERE.
ENCON - re-enables encoders.
ENCRATIOS - leaves the address of an array containing the ratio of encoder count to motor count, specifically the number of encoder counts for 10,000 motor counts.
ENCSET - this presets the encoder counters to correspond with the stepper count e.g. after calibration.
ENCTEST - continuous display of encoder counts (esc to stop).
ENCTOLS - leaves address of an array containing the maximum error for any axis referred to the encoder count (not the motor count), 16 bits per element. The tolerence for axis 1 is obtained with ENCTOLS @, or changed with (val)
ENCTOLS !, axis 2 ENCTOLS 2+, axis 3 ENCTOLS 4 + etc. For an R15 or R19 with 5 encoders the first axis is accessed in the first BYTE (ENCTOLS C@ or (val) ENCTOLS C!), the 5th axis is in the second BYTE. For an R12/R17 with 5 encoders the 5th axis uses the same tolerance as the 4th axis.
ENCVEC - is an execution vector for ENCCHECK. In case of encoder error the word whose CFA is in ENCVEC is executed. Normally contains ENCABORT. To change to a different word enter SET ENCVEC (name)
EDBUF - (edit buffer) constant, address of the text buffer.
EDLOAD - compiles the text in the text buffer (not all versions.
EEP - Encoder Enable Pattern - a variable in which bits 0-5 determine which encoders are enabled.
EFP - Encoder Fit Pattern - a constant determining which encoders are actually fitted - loaded into EEP by START.
ENABLE - enable interrupts.
ELBOW - name of joint 3 (MEP = 4) - revolute robots only.
ELOAD (filename) - gets a text file from the PC running EMU8 into the text buffer EDBUF.
EMPTY - clears all the objects from a ROUTE.
END-THERE - changes the last line of a CARTESIAN ROUTE to the given position and all the other lines are adjusted accordingly. In other words makes the route a relative route that ends at the given position
ENERGISE or ENERGIZE - restores power and holding torque to all joints.
ERASE - erases all the coordinates from the current ROUTE.
ERR - variable containing error number after an ABORT
ERR1 - returns any encoder stepper mismatch for joint 1.
ERR2 to ERR6 - as ERR1 but for the other joints.
EXIT immediately exits the current word
EXTEND - name of Y axis, cartesian robots joint 2 or 3, or R (radius) axis, joint 3, cylindrical robots
F/
FASTSEARCH - does a fast search for an event which causes an interrupt.
FIRST# - line number of ROUTE to start running from. Also applies to LISTROUTE. See also SEQUENCE
FLOAD (filename) - automatically loads and compiles a text file from a PC running EMU8
FN - variable to contain the CFA of a word to be executed on pressing the FN key in TEACH mode.
FORGET (name) - deletes the specified word and all words which were created after it. This is really a FORTH kernel word but extended so that if a USER variable is removed with FORGET then that user area is recovered. If a ROUTE or PLACE is removed the upper memory data area used by that entity is also recovered.
FORTH - selects the FORTH vocabulary in cases where a FORTH word (for example DROP) has been redefined for robot use. The system will then select the word in its original context.
FSTOP - a flag which is set to '1' by ?STOP if the stop button is pressed.
G/
GET - closes the gripper and removes the object name from the POSITION and puts it into OBJECT-HELD.
GF - Globals Fetch. Sends 5 or 6 values from the Cartesian variables starting with X
GLOBAL - sets the currently selected joint to a GLOBAL sense and all remaining joints to a LOCAL sense.
(num) GLOBALS - returns the address of the global motor count for joint number minus one (0 to 5)
GO - sends the arm to current coordinates (inverse kinematics) so you can change any variable and follow with GO
(pos) GOTO - move whole arm to the position specified by the line number of a ROUTE.
(adr) -GOTO - a faster form of GOTO which treats all coordinates as motor coordinates even if in CARTESIAN mode and ignores the execution field (any 'LEARNed word).
GOGET (object) - sends the arm to the location of the object and GETs it (see GET and COLLECT). No longer included from v17 on.
GRIP - close grippers; does not affect other joint selection.
GRIPPER - name of the output bit to the gripper - PA 0
GTYPE - a variable that tells RoboForth if it is an electric or pneumatic gripper.
H/
HAND - selects the wrist pitch motor (MEP = 8) for commands like MOVE, MOVETO, LOCAL, etc.
HERALD - prints ROBOFORTH herald.
HIDE - selects mode whereby characters sent or typed are not echoed back to the screen. After the return at the end of the line a chevron > is printed, no new line, no OK. In HIDE mode all ROUTEs and PLACEs are created in OLD mode (see OLD and NEW. To cancel hide mode enter IOFLAG C0SET (pronounced "I-O-flag see-nought-set") The | character (ascii 7C) does the same.
HOLDING (object) - puts object into the variable OBJECT-HELD so it is listed under OBJECT in the WHERE list.
HOME - a command to return the arm to the home position and also sets the system to all global mode.
I/
(port) IN - reads input port and leaves 8-bit value on stack.
INKEY - returns value of last keyboard key pressed. zero if none pressed.
INKEYPAD - returns value of teach pad key being pressed. zero if none pressed.
(num) INSERT or (num) LINE INSERT - shifts up all the lines from the specified line upwards to make a space, then inserts the current arm coordinates into that line. LINE may be omitted.
(num) 'INSERT (name) - same as INSERT but inserts a ROBOFORTH II or FORTH word instead. LINE may be omitted.
INTFLAG - a 1-byte variable normally containing 0, but contains 80 hex if a non-maskable interrupt has occurred.
INT-TIME - a user variable containing the time in millisecs for a timer interrupt.
INTVEC - a user variable containing the address of a word to be executed upon interrupt using SET INTVEC (word).
(num) INTO - normally used with GRID or ROW - moves the arm to line (num) of the ROUTE using the last line of the ROUTE as a relative approach position by adding this last line to line (num). The last line must be a relative position (R when listed). - cartesian ROUTEs only.
(object) ISAT (pos) - inserts the object into position specified. To clear an object field enter 0 ISAT (pos)
J/
JL - learns joint coordinates when in cartesian mode.
JERK - variable determining rate of acceleration (V17 up).
JMA - Joint Move Absolute. Requires 5 values on stack or 6 for 6-axis robot.
JMR - Joint Move Relative. Requires 5 values on stack or 6 for 6-axis robot.
JOG - same as CARTEACH - similar to TEACH but moves the end effector in increments in cartesian mode, where J1=X-axis, J2=Y-axis, J3=Z-axis, J4=pitch, J5=roll (W), FN=plunge (see PLUNGE) To change increment press space bar.
JOINT - selects joint mode i.e. motor coordinates from CARTESIAN coordinates.
JOINTWHERE - displays joint coordinates even if in CARTESIAN mode.
JR - like REPLACE but replaces with joint coordinates while in cartesian mode. (see JL)
(adr) JUMP - forces processor to jump to address (n)
K/
KEY - system waits for a keyboard key to be pressed, leaving its ASCII value on the stack.
KEYPAD - system holds waiting for a teach pad key to be pressed, then returns hex value of key pressed. (similar to KEY)
L/
LAST# - last line of a ROUTE to be RUN up to and including this line. Also applies to LISTROUTE. May not have a value greater than MOVES. See also SEQUENCE
LEARN - learns a new position into the currently active ROUTE.
'LEARN - same as LEARN but learns a ROBOFORTH II or FORTH word instead of a coordinate.
LEN - a variable containing the length from the shoulder pivot to the wrist pivot after a cartesian move - revolute robots only.
LIFT - name of Z axis, cartesian robots joint 3 or 2, cylindrical robots joint 3.
LIMITS - an array containing the coordinates of the proximity detectors used by CALIBRATE, DATUM and CHECK.
(num) LINE - computes the memory address (in bank 1) of the data for the line number specified within the currently active ROUTE; leaves the address on the stack.
LINE# - variable containing next line number to be executed.
(n) LINES - prints n line feeds on the screen
LISTFLAG - a one byte variable; if = 1 then a ROUTE will be listed as it is executed.
LIST: (route-name) - lists another (not active) ROUTE.
LISTROUTE - lists the positions learned into the currently active ROUTE.
L. - same as LISTROUTE.
LL - LEARN then LISTROUTE.
(num) LOCALS returns the address of the current local motor count for joint number minus one (0 to 5) e.g. 1 LOCALS @
LOOK - scans ahead along the user's command line. If it sees a number leaves it on the stack; if a constant leaves its value on the stack; if a variable or any other word leaves the variable address or parameter address on the stack.
M/
MAXLEN - a constant, maximum possible length from the shoulder pivot to the wrist pivot - revolute robots only.
MCP (Motor Calibrate Pattern) - a 1 byte variable (use C@ C!) where each bit corresponds to a motor; if bit=1 the joint will move with ONLIM or OFFLIM.
MDP (Motor Direction Pattern) - a 1 byte variable (use C@ C!) where each bit corresponds to a motor; if bit=1 the motor will run in reverse.
MEP (Motor Enable Pattern) - a 1 byte variable (use C@ C!) where each bit corresponds to a motor. If the bit=1 the corresponding motor is selected.
MICRO - multiplication factor for micro-stepping. This value is loaded into the DSP by START.
MICROS - an array containing multiplication factors for micro-stepping. These values are loaded into the DSP by START.
MINLEN - A constant, minimum distance in mm * 10 from the wrist pivot to the rotational centre of the waist.
(num) MSECS - delays (num) milliseconds.
MSECS? (num) - event timer: time in milliseconds since last reset. Time value is left on stack
(num) RESETMS - resets event timer to zero.
MODE - Tells you what mode system is in - joint or cartesian, simple or smooth etc.
MOTORS - a constant, number of axes in system.
(val) MOVE - moves selected joint by (val) number of steps. In Cartesian mode requires 3 values: (x) (y) (z) MOVE changes X coordinate by (x), Y coord by (y), Z coord by (z). W and PITCH are left unchanged.
(val) -MOVE - (dash-move) same as MOVE but works in joint mode, requiring a joint selection and single argument even if system in Cartesian mode.
MOVES - a pseudo-variable which holds the number of lines in the currently active ROUTE. This is in memory bank 1 so use MOVES E@
(val) MOVETO - moves selected joint to absolute position (val). In Cartesian mode requires 3 arguments - (X) (Y) (Z) MOVETO moves robot to absolute position X,Y,Z where each value is in mm * 10. W and PITCH are left unchanged. You can change them with !(store) or the TOOLSET command.
(val) -MOVETO - (dash-move-to) same as MOVETO but works in joint mode, requiring a joint selection and single argument even if system in Cartesian mode.
N/
(pfa) NAME - types out the name of the word whose pfa is on the stack, for example OBJECT-HELD @ NAME
(pos) NEAR - sends robot to the near position in a matrix (grid) or row.
(num) NEARAD - leaves the address of the approach position of position (n) in a GRID or ROW i.e. the last line added to line (num) where the last line must be a relative coordinate (marked R).
'NEAR (place-name) GOTO - immediate mode only phrase, drives robot to a PLACE's approach position.
NEW - cancels OLD mode (see OLD)
NEXT - variable containing next memory address available for data
NONALIGN - cancels ALIGN mode.
NORMAL - restores all system variables such as SPEED, acceleration etc. to default values.
O/
OBJECT (name) - creates new object with given name.
OBJECT-HELD - a variable containing the PFA address of an object name.
OBJECTS - lists all objects in system
OBAD - converts a LINE address to the address where an object is stored in a ROUTE line - syntax (num) LINE OBAD. Examples: (object-name) (num) LINE OBAD ! or 0 (num) LINE OBAD !
OFF - syntax (adr) n OFF - turns bit n of output port address (adr) to a zero. Open collector goes open circuit.
OFFLIM - low level routine drives selected axis/axes off the calibration proximity detector(s).
OFFSPD - a constant containing speed that axes move off the calibration proximity detectors.
OLD - selects mode whereby when a ROUTE or PLACE is created it is matched up with an existing entry in the data area. In this way a ROUTE recovers existing data instead of having to LEARN all over again and a PLACE picks up the original coordinates rather than present position of robot.
ON - syntax (adr) n ON- turns bit n of output port address (adr) to a logic true. Open collector turns on. example: PA 1 ON
ONLIM - low level routine drives selected axes onto the calibration proximity detectors.
ONSPD - a constant determining speed that axes search for the calibration proximity detectors.
ORIGIN - a cartesian position where X,Y,Z,W, PITCH are all zero.
(num) (port) OUT - outputs 8-bit value (num) to (port).
OUTER - re-entrant outer interpreter.
P/
P - prints binary representation of input port PB
PA - address of primary output port (used by gripper etc.)
PB - address of primary input port (proximity detectors).
PITCH - a variable containing angle of hand to horizontal in cartesian mode.
PLACE (name) - creates a new PLACE (named position) with the given name. Thereafter using (name) alone drives the robot to the position at the time of creation. See also PLEARN and APPROACH.
PLACES - lists all PLACEs so far created.
PLEARN - learns coordinates into a PLACE.
(val) PLUNGE - move the end effector (val) * 0.1mm in the direction it is pointing. On an R19 it applies to angles in the X-Y plane and ALIGN must be used first.
POINT (name) - creates a new entity which contains the current cartesian position. Usage (name) GOTO (XGOTO in v10.0)
POINTS - lists all points so far created.
PORT - obsolete word, see controller manual for details of user ports.
POSITION - a variable containing the parameter field address of the last position accessed by name or (num) LINE.
POSNS - the number of positions in a ROW, in a GRID it is the number of positions in each row i.e. number of columns.
PP - continuous display of PB in binary (P) (esc to stop).
PREVIOUS - restores previous cartesian position to the cartesian variables W,X,Y,Z, PITCH after an error.
PROGPIA - reprograms the PIA ports (part of START).
PSAVE - saves current ROBOFORTH RAM image to flash memory.
PURGE - empties the stack
PUT - opens the gripper to position zero, removes object name from OBJECT-HELD and puts the object name into the current POSITION i.e. last position accessed by name or (num) LINE
R/
RECEIVE - downloads data from the PC to controller memory, syntax: (start-addr) (#bytes (multiple of 256)) RECEIVE DROP
RELATIVE - starts count of a local position relative to the starting position.
REPEATS - set the number of times a route RUN repeats from the beginning of the route. (v17.3 up)
(pos) REPLACE or (num) REPLACE - replace the coordinates of the named position or line number with the coordinates of where the robot is now.
'REPLACE - same as REPLACE but replaces the line with a FORTH or ROBOFORTH II word. Syntax: (num) LINE 'REPLACE (word) or (num) 'REPLACE (word)
(num) RESERVE - reserves extra space for (num) lines to be learned in a ROUTE. No use once a new data entity has been created.
RESET - software reset, leaving project intact.
RESTART - software reset executing the word whose CFA is currently in TURNKEY.
RESUME - resume motion to the Cartesian target position before the robot was stopped by the stop button.
RESTORE - restores original SPEED value after using ADJUST or SMOOTH.
RETRACE - same as RUN but runs ROUTE in reverse order.
REVERSE - sets all selected motors to reverse.
RETURN - return from interrupt. Must be the last word in a definition which is executed by timed or input interrupts.
RLEARN - learns a relative position into the route. Usually used with ROW and GRID
RNORM - restores the start and finish lines of a ROUTE changed by SEQUENCE to first and last lines.
ROBOFORTH - erases all user dictionary down to the core ROBOFORTH words.
?RUN - leaves 0 if DSP is ready, 1 if busy. Other status values indicate that a line contains GRIPPER or SETPA and this is used to sychronize I/O activity with the CPU.
ROBOT - selects the robot vocabulary again after using the word FORTH (see above).
RON - a constant in some systems only determining acceleration and deceleration in ONLIM.
ROUTE (name) - creates a new ROUTE with the given name and makes it the currently active ROUTE. Thereafter using (name) alone activates the ROUTE so that RUN, LISTROUTE, GOTO etc. apply to this ROUTE.
ROUTES - lists all ROUTEs so far created.
ROW - starts a procedure to generate an 1-dimensional array of positions given only the positions of each end.
ROWS - the number of rows in a GRID
RTYPE - changes the current ROUTE type to from its current type to current mode i.e. JOINT to CARTESIAN or vice versa.
RUN - runs the current ROUTE in sequence line by line (see SEQUENCE and RETRACE)
RUN-LIST - the name of the start of the data area.
S/
(num1) (num2) SEQUENCE - sets a limited range of lines to be RUN.
SEGMENTED - opposite of CONTINUOUS i.e. robot will stop momentarily at leach line in a ROUTE.
SEGTIME - time DSP sets for each segment i.e. the distance between one line of a route and the next is completed in this time (if possible). See TIMED SET - sets an execution vector (e.g. FN, CRITERION, STOPVEC, DSPVEC, INTVEC, ENCVEC)
SETHOME - sets all WHERE coordinates to zero; same as SET-GLOBAL- HOME if in GLOBAL (absolute)mode, same as SET-LOCAL-HOME if in LOCAL (relative) mode, or according to MSP if MIXED.
SETLIMITS - over-writes the array LIMITS with the current robot coordinates.
SET-LOCAL-HOME - sets the local position to all zeros, does not affect the global position counts.
SET-GLOBAL-HOME - sets the global position to all zeros, does not affect the local position counts.
(num) SETMEP - ORs the new bit pattern in (num) into MEP
(num) SETPA - a word to include in a route using insert function. When encountered in a CONTINUOUS RUN the argument learned with SETPA is returned from the DSP in ?RUN
SETTLE - settling time function to prevent encoders being read too early. The time, in milliseconds, is in ' SETTLE 2+
SETTINGS - displays the values in all the motor control variables and permits entry of new values for each variable. Just press return to retain existing value.
SHOULDER - name of joint 2 (MEP=2) - revolute robots only.
(adr) SHOW - displays the coordinates at address (adr)
SLOWSEARCH - does a slow search for an event.
(num) SIZE - sets initial size of a newly created ROUTE in lines.
SMOOTH - selects interpolated motion and reduces speed to avoid too tight errors.
SPEED - controls speed, same as CSPEED, typical values from 500 to 20000
START - reprograms the output port, re-initialises the acceleration profile, motor phase patterns, sets speed etc. to default value, sets the current position to all zeros (global and local) deselects all joints and sets the sense of all joints to GLOBAL.
STARTOVER - effectively erases all the data in the run-list - actually only resets the pointer to the start of the run-list which means that OLD can be used to recover the old data.
START-HERE - changes the start of a CARTESIAN ROUTE to where the robot currently is and changes the other lines by the same amount. In other words makes the route a relative route that starts at the robots current position.
START-ADDR - this is a function leaving the address of the header of the currently active ROUTE. START-ADDR @ yields the next available address for the next data entity.
START-TIMER - starts timer interrupts.
(Val) STEPS - all motors selected by TELL (joint-name) move the number of steps specified. If a motor's MDP bit = 1 it moves backwards. If (val) is negative then all motors move backwards except motors with MDP bit = 1 which move forward. The steps are not counted (don't appear in WHERE), however you may insert UPDATE-WHERE between (val) and STEPS.
STOP - stops the robot if running under DSP control.
STOPABORT - aborts with stop button message and ERR=3.
STOPACC - much higher value for ACCEL used to decelerate motors in an emergency.
STOPVEC - a variable to contain the CFA of word to be executed by vectored execution if the stop button is pressed.
STOP? - leaves true if the stop button is being pressed.
?STOP - if the stop button is pressed sends STOP command to the DSP and sets flag FSTOP to 1.
STOPCHECK - Checks stop button
STOP-TIMER - stops timer interrupts.
T/
?TERMINAL - leaves true on stack if escape key has been pressed.
TARGET - address to which motor coordinates are assembled by TRANSFORM. Can use TARGET -GOTO
TEACH - enters "teach mode" for control by holding down single keys. To change speed press the space bar.
(TEACH) - same as TEACH but does not ask for creep speed first. -See CREEP-FACTOR
TELL - clears all previous joint selections ready for a new selection by joint name - for commands like MOVE, MOVETO, LOCAL.
TIMED - sets DSP to a fixed time interval between lines of a route. Always use CONTINUOUS TIMED. To cancel TIMED mode just enter CONTINUOUS or SEGMENTED
TON - the length of time in uSecs for the on-pulse in PWM control of electric gripper.
TOOL-LENGTH - distance in units of 0.1mm from hand axis (pivot) to point within end effector to be positioned in cartesian mode. 5-axis systems only.
TOOLSET - change hand axis angles and tool length.
TRACK - name of joint 1 on cartesian robots, or joint 5 on cylindrical robots or joint 6 on track mounted revolute robots
TRACKSPEED - speed limit for the track on an cartesian robots.
TRANSMIT - uploads data from controller memory to EMU8, syntax: (start-addr) (#bytes (multiple of 256)) TRANSMIT
TRANSFORM - transforms from values in the variables X Y Z PITCH, W and TOOL-LENGTH or OFFSET to motor coordinates which are assembled at address TARGET.
(val) TWIST - turns the wrist by value-controls joint 5 (MEP=16).
U/
UNLEARN - removes the last line learned in a ROUTE.
UNGRIP - opens the gripper.
UNTWIST takes out any twist in the wrist.
UP - moves robot back to the approach position of a GRID or ROW.
(val) UPDATE-WHERE - updates WHERE with the value according to bits set in MEP. If an MEP bit is '1' (true) then the amount that motor has moved is added into the motor coordinate. If the corresponding MDP bit is '1' the value is subtracted from the motor coordinate. The value (val) is left behind on the stack.
UPSPEED - speed limit used when the lift axis is going up.
USAVE - saves user software and data to flash memory
(num) USECS - delays (num) microseconds. resolution is 10 microseconds
USER (name) - creates a user variable. also see defining words
V/
VARIABLE (name) - creates a variable. also see defining words
VIEW (Pos) - view the coordinates of the position.
'VLIST usage 'VLIST (word) lists all words in the dictionary of the same type as the example word which follows 'VLIST.
W/
W - variable containing target value times 0.1 degrees of rotation of wrist (twist or roll) in cartesian mode.
WAIST - name of base rotate movement (MEP=1) - not cartesian robots
(port) (bit) (1or0) WAIT - wait for specified bit of specified port to go to 1 or 0 as given - 3 arguments on stack.
WHERE - returns the current position of the arm i.e. all the motor coordinates.
WHEREIS (object) - returns the location (position) of the object.
WHICH - returns which ROUTE is currently active.
WORKSPACE - Cartesian robots only. An array containing 6 16-bit (2-byte) elements, representing:
element function address 0: maximum X value WORKSPACE 1: maximum Y value WORKSPACE 2 + 2: maximum Z value WORKSPACE 4 + 3: minimum X value WORKSPACE 6 + 4: minimum Y value WORKSPACE 8 + 5: minimum Z value WORKSPACE 10 +
WITHDRAW - after invoking a PLACE name, WITHDRAW pulls the robot back from the target position to the approach position.
WRIST - selects the wrist twist motor for commands like MOVE, MOVETO, LOCAL, etc. - (joint 5, MEP=16 on revolute robots joint 4, MEP=8 on cylindrical robots )
WRU - (Who are you?) - returns the serial number of the robot.
WWW - (What Went Wrong?) - tells you why the robot stopped.
X/Y/Z/
X - variable containing target value times 0.1mm for X coordinate in cartesian mode.
(pos) XGOTO - move whole arm to the position specified in a specfied address, or by name or by (num) LINE. The position will be assumed to contain motor coordinates if in JOINT mode, or cartesian coordinates if in CARTESIAN mode. The address can be in either bank, determined by the value of BANK 0 or 1.
Normally the data entity used will set the bank to the correct value. If not you will need to write BANK C0SET or BANK C1SET according to which bank the data will be in.
XRETURN - return from a timer interrupt and then disables further interrupts. Must be the last word in a definition which is executed by timed interrupts.
(value) XTOOL - moves the tool at right angles to it's orientation by (value) * 0.1mm i.e. X direction in TOOL coordinates. Only available with the Android teach console.
Y - variable containing target value times 0.1mm for Y coordinate in cartesian mode.
(value) YTOOL - moves the tool at right angles to it's orientation i.e. Y direction in TOOL coordinates. Only available with the Android teach console. Z - variable containing target value times 0.1mm for Z coordinate in cartesian mode.
(value) ZTOOL - moves the tool in direction it is pointing, same as PLUNGE.