home *** CD-ROM | disk | FTP | other *** search
- .ND
- .EQ
- delim $$
- .EN
- .NH 1
- Introduction
- .PP
- This manual describes
- the first version of the RCCL robot programming system.
- The reader is assumed to be familiar with the C programming language [1],
- and with the UNIX operating system.
- A thorough understanding of the control and programming techniques
- described by Paul in [2]
- is highly recommended if not mandatory.
- The design philosophy of RCCL is described in [3].
- .NH 1
- Overview
- .PP
- Using RCCL requires the user to be aware of the
- hardware and software components.
- The hardware involves a VAX computer operated under UNIX.
- A special high speed input-output interface [4] installed on the
- VAX Unibus extension establishes the communication with a
- Unimate robot controller [5].
- The controller's hardware consists of an LSI1-11 microprocessor and several
- interfaces mounted on a Qbus (serial, parallel, adc/dac, and
- host machine interfaces).
- The LSI-11 microprocessor controls
- six 6503 joint processors via a special parallel
- interface.
- The joint processors control the manipulator's joints via
- digital and analog circuitry.
- .PP
- Software components can be listed in terms of levels.
- Starting at the lowest level, we find the
- .I servo
- code running in each joint
- processor.
- A
- .I superviser
- program,
- loaded in the LSI11 is driven by a hardware clock
- interrupt.
- Each time sample, the
- .I superviser
- program gathers data from the manipulator state : joint
- positions and torques, front panel switch register content, analog
- conversion readings, interrupts the VAX and transmits the data.
- It then enters a wait state until the VAX sends back low level commands that
- are transmitted to the joint processors.
- Interrupts are handled in the VAX by mean of a specialized
- .I
- device driver.
- .R
- Each time an interrupt occurs in the VAX,
- the manipulator state is monitored by a
- .I
- real time robot interface
- .R
- that checks for limit conditions.
- Error conditions are excessive joint rates or motor currents.
- The manipulator's state data is stored in a C structure available as a global
- variable [6].
- The
- .I
- real time interface,
- .R
- after receiving the manipulator's
- state information, calls a initial user's function,
- examines the content of a second global C structure describing all the
- possible command combinations.
- It checks for validity, translates the requests into low level commands
- and transmit them to the robot controller.
- A second user function is then called and can run for the remainder of the
- sample period.
- The
- .I
- real time interface
- .R
- serves the purpose of a robot controller user's interface and its
- functions and operation
- are described in [6].
- .PP
- The
- .I setpoint
- process, or trajectory generator is part of RCCL, and uses the
- .I
- real time interface
- .R
- to control the manipulator and obtain the manipulator's state.
- The
- .I setpoint
- process is interrupt driven and acts according to asynchronous motion
- requests specified in the user's program via RCCL primitives.
- .bp
- .NH
- Tutorial Introduction
- .PP
- The first program we shall introduce,
- uses a reference coordinate frame located at the base of the
- manipulator whose shoulder is at 864 mm above the base.
- The transform $T6$ describes the position of a frame attached to
- the last link of the robot originated at the point of meeting of
- the axes of the last three joints, with respect to the shoulder.
- We want to move the manipulator at a position located at
- 600 mm in the X direction, 100 mm in the Y direction, and 800 mm
- in the Z direction with respect to the reference coordinate frame.
- We also want that the last link points downward.
- The program may look like:
- .br
- .cs R 23
- .DS L
- #include "rccl.h"
-
- pumatask()
- {
- TRSF_PTR t, b;
- POS_PTR p0;
-
- t = gentr_trsl("T", 0., 0., 864.);
- b = gentr_rot("B", 600. , 100., 800., yunit, 180.);
-
- p0 = makeposition("P0", t, t6, EQ, b, TL, t6);
-
- move(p0);
- move(park);
- }
- .DE
- .cs R
- .PP
- The file
- .B rccl.h
- contains C structure type definitions and external
- entry points the same way the system file ``stdio.h'' does.
- It gives access to what users programs may need in order to
- use RCCL functions, structures, and variables.
- .PP
- The variable declarations include the predeclared types
- TRSF_PTR, a pointer to a transformation
- structure, and POS_PTR, a pointer to a position structure.
- The system builds the transformations matrices needed to describe
- the task via the
- .B gen_trsl
- and
- .B gen_rot
- functions.
- The reference coordinate is called ``T'' and is set as a pure translation.
- As for all the RCCL functions that dynamically
- allocate memory space, the first
- argument is a string of characters naming the created object.
- This name is purely arbitrary and can be set to the empty string ("").
- However, giving meaningful names is a good idea because
- RCCL uses them in many occasions to print informative messages.
- The remaining arguments of the
- .I gentr_trsl()
- function are the X, Y, and Z values of the $p$ (position)
- vector of the transform.
- The rotational part is automatically set to the $unit$ rotation.
- The function
- .I gentr_rot()
- allocates memory and sets the positional part and the rotational part
- of the ``B'' transform.
- Arguments 1, 2, 3, and 4 have the same meaning as for
- .I gentr_trsl().
- Among several possible ways to specify rotations, we use here
- a rotation around a vector.
- The variable `yunit', which is of the type VECT_PTR, is a pointer
- to a vector.
- This variable is provided by RCCL as a pointer to
- a vector whose value is {0., 1., 0.}.
- .FS
- RCCL is systematically coded according to the conventions of the
- C language Version 6.
- Recent versions of C allow the passing by value of
- structures as function arguments.
- Although one may use these features in the programs, none of the
- RCCL functions make use of them and structure arguments are
- always passed by address.
- .FE
- The rotational part of the ``B'' transform is set to a 180 degrees rotation
- around the Y unit vector.
- (The fact that the Z direction of the $T6$ transform is pointing in
- direction of the last link of the manipulator must be kept in mind).
- The Z axis of the ``B'' transform is now pointing downward, because
- ``B'' is described with respect to ``T'' whose Z direction points upward.
- .PP
- It is now time to set up a position equation using a call to
- .I makeposition.
- .I Makeposition
- returns a pointer to a ring data structure that is used by the
- .I move
- primitive.
- It accepts a variable number of arguments.
- The first one is the name of the position.
- Up to the `EQ' constant, the list of arguments make up
- the left hand side of the position equation.
- Then comes the list of transforms making up the right hand side.
- The constant `TL' introduces the transform that we choose to be
- the
- .I tool
- transform.
- The
- .I tool
- transform can be any of the frames contained in the equation, provided
- that it gives meaningful results, more on that later.
- For now, we can say that most of the
- time, $T6$ or one of the frames described with respect to $T6$ in the
- left hand side of the equation will be chosen.
- We obtain the following equation :
- .EQ
- T~T6~=~B
- .EN
- .PP
- The first
- .I move
- request causes the manipulator to move such that the position equation
- is satisfied.
- In practice the robot will not exactly reach ``P0'', but
- will perform a transition close to it before going back to ``PARK''.
- The `park' position pointer is build into the system.
- .PP
- Before proceeding further, we shall add two modifications to
- this first example. We replace:
- .br
- .cs R 23
- .DS L
- move(p0);
- move(park);
- .DE
- .cs R
- by:
- .br
- .cs R 23
- .DS L
- setmod('c');
- move(p0);
- stop(0);
- move(park);
- .DE
- .cs R
- .PP
- By default, RCCL tasks start in
- .I joint
- mode.
- By calling
- .I setmod()
- we ask for the moves to be performed in
- .I Cartesian
- mode, the
- .I tool
- frame, here $T6$, move along a line joining the ``PARK'' position
- and the ``P0'' position.
- The
- .I stop
- statement causes the manipulator to stop during a null time at ``P0'',
- that is to say, to bring the velocity to zero.
- In other words, it will actually reach the position ``P0''.
- The $T6$ transform, during the travel to ``P0'', will be evaluated
- at sample time intervals as:
- .EQ
- T6~=~T sup -1~B~DRIVE
- .EN
- The purpose of the $DRIVE$ transform is to produce a straight path
- motion [2].
- Most of the time, the position equation will include one or
- several transforms to describe the end effector.
- This can be achieved by creating one more transform and adding
- one argument to the position equation.
- .br
- .cs R 23
- .DS L
- e = gentr_trsl("E", 0., 0., 170.);
-
- p0 = makeposition("P0", t, t6, e, EQ, b, TL, e);
- .DE
- .cs R
- Now the location described by the transformation ``E'' with respect to $T6$
- will travel along
- a straight Cartesian path and $T6$ will be evaluated as :
- .EQ
- T6~=~T sup -1~B~DRIVE~E sup -1
- .EN
-