home *** CD-ROM | disk | FTP | other *** search
/ Between Heaven & Hell 2 / BetweenHeavenHell.cdr / 500 / 470 / rccl015 < prev    next >
Text File  |  1987-03-02  |  56KB  |  1,739 lines

  1. .ND
  2. .EQ
  3. delim $$
  4. .EN
  5. .nr H1 5
  6. .NH 1
  7. Sensor Integration
  8. .PP
  9. By using sensors, the user has the ability to write
  10. programs that may depend on information acquired at run time.
  11. The behavior of the manipulator can be influenced
  12. by modifying the locations it is moving to or by interrupting a motion.
  13. If the location can be determined ahead of time, we shall call that
  14. presetting the world model.
  15. A special case is the transforms initializations.
  16. If the locations can be determined synchronously and permit us
  17. to influence the manipulator's path, we shall call that tracking.
  18. If the locations can be determined by stopping the manipulator on
  19. condition, we shall call that guarded motions.
  20. If the final position of the manipulator is to be retained for
  21. the determinations of locations, we shall call that updating the world
  22. model.
  23. .NH 2
  24. Presetting the World Model.
  25. .PP
  26. In the section `Synchronization' we have already met such a situation.
  27. The example of a program interacting with a user was given :
  28. .br
  29. .cs R 23
  30. .DS L
  31.         for (; ; ) {
  32.                 printf("enter Z increment ");
  33.                 scanf("%f", &iz);
  34.                 b->p.z += iz;
  35.                 move(p);
  36.         }
  37. .DE
  38. .cs R
  39. The
  40. .I hold
  41. transform feature allowed us the specify different locations ahead
  42. at time and no synchronization is specified.
  43. .PP
  44. Let us consider the integration of a computer vision system.
  45. We assume that a camera has been attached to the link 4 of
  46. the PUMA manipulator.
  47. The computer vision is described in terms of a functions `snapshot'
  48. which is supposed to take a picture of the scene and store it in memory, and
  49. of a function `getobj' able to extract the position and orientation
  50. of an object in the camera coordinate frame.
  51. The operation of taking the picture is expected to be short but the task
  52. is programmed in such a way that the processing time of `getobj' does not
  53. require to stop the arm.
  54. The strategy consist of moving the manipulator toward a position
  55. where we expect an object to be captured in the field of the camera.
  56. We synchronize the program such as the picture is taken at a given
  57. point of the trajectory.
  58. We also record at this instant the position of the manipulator
  59. given by $T6$ and we reconstruct the camera coordinate frame from
  60. the transform $U5$ internally maintained by the system.
  61. We could also compute the values of the transform $T4$ since we can know
  62. at any moment the joint angles values (see include files).
  63. Thus we have all the information necessary to perform an
  64. approach motion where the object has been found, grasp it, and move it
  65. to some other place.
  66. .PP
  67. A bare bone version of the task is described
  68. in terms of three position equations : the position where to expect
  69. an object to be seen by the camera, the position where to grasp the object,
  70. and the position where to put it :
  71. .br
  72. .cs R 23
  73. .DS L
  74.      1  #include "rccl.h"
  75.      2  #include "hand.h"
  76.      3  #include "which.h"
  77.      4  #include "kine.h"
  78.      5
  79.      6  pumatask()
  80.      7  {
  81.      8          TRSF_PTR  z, e, cam, o, coord, t6r, u5i, expect, drop;
  82.      9          POS_PTR look, get, put;
  83.     10
  84.     11          z = gentr_trsl("Z",  0.,  0., 864.);
  85.     12          e = gentr_trsl("E" , 0. , 0. , 170.);
  86.     13          cam = gentr_rot("CAM", 0., 0., 50., xunit, 90.);
  87.     14          expect = gentr_rot("EXPECT", 500. , 100., 600., yunit, 180.);
  88.     15          drop = gentr_rot("DROP", 400. , -100., 500., yunit, 180.);
  89.     16          o = newtrans("O", hold);
  90.     17          coord = newtrans("COORD", hold);
  91.     18
  92.     19          u5i = newtrans("U5I", varb);
  93.     20          t6r = newtrans("T6R", varb);
  94.     21
  95.     22          look = makeposition("LOOK", z, t6, e, EQ, expect, TL, e);
  96.     23          get = makeposition("GET", t6, e, EQ, coord, cam, o, TL, e);
  97.     24          put = makeposition("PUT" , z, t6, e, EQ, drop, TL, e);
  98.     25
  99. .DE
  100. .cs R
  101. .br
  102. .cs R 23
  103. .DS L
  104.     26
  105.     27          setvel(200, 100);
  106.     28          for (; ; ) {
  107.     29                  move(look);
  108.     30                  waitas(goalpos == look && look->scal > .8);
  109.     31                  snapshot();
  110.     32                  Assigntr(t6r, t6);
  111.     33                  Invert(u5i, &sncs_d.u5);
  112.     34                  Trmult(coord, t6r, u5i);
  113.     35                  if (!getobj(o)) {
  114.     36                          break;
  115.     37                  }
  116.     38                  get->end = 0;
  117.     39                  distance("dz", -30.);
  118.     40                  move(get);
  119.     41                  move(get);
  120.     42                  stop(50);
  121.     43                  distance("dz", -30.);
  122.     44                  move(get);
  123.     45
  124.     46                  waitfor(get->end);
  125.     47                  waitfor(get->end);
  126.     48                  CLOSE;
  127.     49                  printf("closing\\\\n");
  128.     50                  move(put);
  129.     51                  waitfor(put->end);
  130.     52                  OPEN;
  131.     53                  printf("opening\\\\n");
  132.     54          }
  133.     55          move(park);
  134.     56  }
  135.     57
  136.     58  snapshot()
  137.     59  {
  138.     60          printf("snap\\\\n");
  139.     61  }
  140.     62
  141.     63  getobj(t)
  142.     64  TRSF_PTR t;
  143.     65  {
  144.     66          static int number = 5;
  145.     67
  146.     68          Trsl(t, 0., 0., 200. + number * 30.);
  147.     69          Rot(t, yunit, 10. * number);
  148.     70          return(number--);
  149.     71  }
  150. .DE
  151. .cs R
  152. .PP
  153. Line 1 includes RCCL declarations.
  154. Line 2 includes the file
  155. .B hand.h
  156. that contain the two macros `OPEN' and `CLOSE' to actuate the pneumatic
  157. gripper.
  158. Line 4 includes the file
  159. .B kine.h
  160. that contains manipulator dependent informations about the kinematics.
  161. This file contains the structure declarations and external
  162. declarations of variables internally used by RCCL.
  163. Since this file depends on the manipulator type it must be preceded
  164. with the definition of the particular manipulator
  165. (`PUMA' for the Puma 600, `STAN' for the stanford arm).
  166. The file
  167. .B which.h
  168. included line 3 contains the line : ``#define PUMA'' that describe
  169. the current implementation.
  170. We are primarily interested in the variable called
  171. .B snsc_d
  172. declared in
  173. .B kine.h
  174. as :
  175. .br
  176. .cs R 23
  177. .DS L
  178. typedef struct sincos {
  179.         real c1, s1, c2, s2, c23, s23, c3, s3, c4, s4, c5, s5, c6, s6;
  180.         real d1x, d1y, d1z, r1x, r1z, d2x, d2y, d2z, d3x, d3y, d3z;
  181.         real h;
  182.         TRSF u5;
  183. } SNCS, *SNCS_PTR;
  184.  
  185. extern  SNCS  sncs_d;
  186. .DE
  187. .cs R
  188. The elements of
  189. .B sncs_d
  190. are kinematic parameters updated at sample time that the user may
  191. use.
  192. For the Puma manipulator,
  193. the first line is the list of sines and cosines values of each joint
  194. angles.
  195. The second and third line exhibit the coefficients
  196. of the Jacobian matrix that contain multiplications computed
  197. in link 4 [9].
  198. The fourth line of type `TRSF' is the transform $U5$ and we shall
  199. make use of it.
  200. .PP
  201. Back to the program, after the pointer declaration we find, lines 11 through 20,
  202. the allocation of transforms.
  203. For simplicity, we will name them the same way as
  204. the frames that they describe.
  205. .IP "Z : "
  206. a reference frame at the base of the manipulator.
  207.  
  208. .IP "E : "
  209. the end effector frame.
  210.  
  211. .IP "CAM : "
  212. the camera frame described with respect to link 4.
  213.  
  214. .IP "EXPECT : "
  215. the position where we expect to find an object in the camera field
  216. with respect to the Z frame.
  217.  
  218. .IP "DROP : "
  219. the position from where we would like the manipulator to drop the
  220. object.
  221.  
  222. .IP "O : "
  223. The position of the object in camera coordinates that we declare as
  224. .I hold
  225. since it will be changed at during the task execution.
  226.  
  227. .IP "COORD : "
  228. The position of the camera in base coordinates that is changing as the
  229. manipulator moves.
  230.  
  231. .IP "U5I and T6R : "
  232. auxiliary transforms that are used to hold the inverse of U5 and a copy
  233. of T6 at the moment of taking the picture.
  234. They will be used to compute the transform COORD, but are not used
  235. in a position equations.
  236. .PP
  237. The three calls to makeposition, lines 22, 23, and 24 define to following
  238. transform graphs :
  239. .br
  240. .cs R 23
  241. .DS L
  242. LOOK :
  243.  
  244.            T6     E
  245.          -----> ----->
  246.         |             |
  247.         |             |
  248.          <----- ----->
  249.            Z    EXPECT
  250. .DE
  251. .cs R
  252. .PP
  253. This first graph is quite ordinary.
  254. .br
  255. .cs R 23
  256. .DS L
  257. GET :
  258.  
  259.            T6     E
  260.          -----> -----> <-----
  261.         |                    |
  262.         |                    |
  263.          <----- -----> ----->
  264.           COORD  CAM     O
  265. .DE
  266. .cs R
  267. This graph describes the final position entirely in manipulator coordinates.
  268. The transforms $COORD$ and $O$ are measured at the moment of taking
  269. the picture and their values memorized in the motion queue.
  270. It is mapped on the equivalent graph :
  271. .br
  272. .cs R 23
  273. .DS L
  274. GET :
  275.                  CAM     O
  276.                 -----> ----->
  277.                |             |
  278.           T4   |   U5    E   |
  279.          ----->|-----> ----->|
  280.         |             |      |
  281.         |    T6       |      |
  282.         |------------>       |
  283.         |                    |
  284.          <----- -----> ----->
  285.           COORD  CAM     O
  286. .DE
  287. .cs R
  288. from which we can derive :
  289. .EQ
  290. ~COORD~=~T6~U5 sup -1
  291. .EN
  292. .br
  293. .cs R 23
  294. .DS L
  295. PUT :
  296.  
  297.         T6         E
  298.          -----> ----->
  299.         |             |
  300.         |             |
  301.          <----- ----->
  302.            Z    DROP
  303. .DE
  304. .cs R
  305. .PP
  306. Again, an ordinary graph.
  307. .PP
  308. Statement, line 27, sets the velocity and one can notice that
  309. the motion type is left in
  310. .I joint
  311. mode, since we are more interested in the end of path segment
  312. position than with the trajectories.
  313. The body of the program is essentially a loop that will exit when the
  314. function `getobj' returns zero value.
  315. The function `getobj' is simulated and returns five different successive
  316. values for the $O$ transform.
  317. .PP
  318. At the beginning of the loop, line 29, a motion is requested toward
  319. the `LOOK' position.
  320. The program is then synchronized such that `snapshot' is called at
  321. 80 per cent of the trajectory.
  322. Note that a `waitas(look->scal > .8)' statement may not be sufficient
  323. since after execution of the first loop the value of `look->scal'
  324. is left at 1. as a side effect of the previous loop,
  325. and no synchronization would be achieved.
  326. Values of $T6$ and $U5$ are copied on the fly, and the $COORD$
  327. transform value computed, lines 32 to 34.
  328. The function `getobj' has the remaining trajectory time
  329. to obtain of value for $O$.
  330. An `approach - grasp - depart' sequence is then performed before
  331. the next loop, lines 39 to 44.
  332. .PP
  333. This program is only a sketch and many improvements
  334. are possible.
  335. For example, we may like to interrupt the motion and proceed to
  336. the grasp sequence as soon as a value for $O$ is obtained.
  337. We shall see in the next section how to achieve this result.
  338. Another variation would be to introduce a conveyor carrying objects
  339. in the vision field of the camera.
  340. The only required modifications would be the position equation for `GET' :
  341. .br
  342. .cs R 23
  343. .DS L
  344.         get = makeposition("GET", z, t6, e, EQ, conv, coord, cam, o, TL, e);
  345. .DE
  346. .cs R
  347. This is because the object position information is entirely contained
  348. in the transforms $T4$, $CAM$, and $O$, and the position `GET'
  349. would be tracking the conveyor.
  350. .NH 2
  351. Guarded Motions
  352. .PP
  353. This section explains how to interrup a motion
  354. on condition.
  355. Interrupting a motion can allow us to stop or to start the arm,
  356. to suspend or resume a motion toward a position.
  357. This can be achieved in all cases by setting the flag called
  358. .B nextmove
  359. at a non zero value.
  360. This causes the motion currently being performed to be interrupted
  361. and the next in the queue to begin.
  362. The value to which the flag
  363. .B nextmove
  364. has been set is returned in the `code' field of the structure `POS',
  365. described earlier.
  366. When using this feature, the user must be careful not to conflict
  367. with values that have a predetermined meaning for RCCL :
  368. .br
  369. .cs R 23
  370. .DS L
  371. #define OK      -1
  372. #define LIMIT   -2
  373. #define ONF     -3
  374. #define OND     -4
  375. .DE
  376. .cs R
  377. For example, one could use only positive values.
  378. .PP
  379. There are basically two ways of using the
  380. flag
  381. .B nextmove.
  382. It can be set either from a background function,
  383. or from the user's foreground process.
  384. Let us illustrate this by an example using a simple sensor which
  385. is a small linear potentiometer.
  386. The distance of which the shaft is inside the body of the potentiometer
  387. can be measured through analog channels.
  388. The robot controller
  389. performs analog to digital conversions
  390. when specified via the function
  391. .B adcopen
  392. and the values can be read from a global array updated at sample intervals [6].
  393. We will make use of this information to program guarded motions.
  394. .br
  395. .cs R 23
  396. .DS L
  397.      1  #include "rccl.h"
  398.      2  #include "hand.h"
  399.      3  #include "rtc.h"
  400.      4  #include "umac.h"
  401.      5
  402.      6  extern struct how how;
  403.      7
  404.      8  static int sensor;
  405.      9
  406.     10  #define TOUCHED 10
  407.     11
  408.     12  pumatask()
  409.     13  {
  410.     14          int touchfn();
  411.     15          TRSF_PTR z, b1, b2, fing, getit, flip;
  412.     16          POS_PTR  get, p1, p2;
  413.     17          int q;
  414.     18
  415.     19          z = gentr_trsl("Z",  0.,  0., 864.);
  416.     20          b1 = gentr_trsl("B1", 600. ,-200., 400.);
  417.     21          b2 = gentr_trsl("B2", 600. ,-100., 400.);
  418.     22          fing = gentr_rot("FING", 0., 0., 200., zunit, -90.);
  419.     23          getit = gentr_rot("GETIT", 600. , 0., 600., yunit, 180.);
  420.     24          flip = gentr_rot("FLIP", 0., 0., 0., yunit, 180.);
  421.     25
  422.     26          p1 = makeposition("P1" , z, t6, fing, EQ, b1, flip,TL , fing);
  423.     27          p2 = makeposition("P2" , z, t6, fing, EQ, b2, flip,TL , fing);
  424.     28          get = makeposition("GET", z, t6, EQ, getit, TL, t6);
  425.     29
  426.     30          setvel(300, 100);
  427.     31          move(get);
  428.     32          waitfor(completed);
  429.     33          OPEN;
  430.     34          printf("put the sensor in the jaws ");
  431.     35          QUERY(q);
  432.     36          CLOSE;
  433.     37          printf("go ahead ");
  434.     38          QUERY(q);
  435.     39          if (q == 'n') {
  436.     40                  move(park);
  437.     41                  return;
  438.     42          }
  439. .DE
  440. .cs R
  441. .br
  442. .cs R 23
  443. .DS L
  444.     43          sensor = adcopen(7);
  445.     44          setvel(100, 100);
  446.     45          for (; ; ) {
  447.     46                  p1->end = p2->end = 0;
  448.     47                  move(p1);
  449.     48                  evalfn(touchfn);
  450.     49                  setime(0, 0);
  451.     50                  distance("dz", 100.);
  452.     51                  move(p1);
  453.     52                  move(p1);
  454.     53
  455.     54                  move(p2);
  456.     55                  evalfn(touchfn);
  457.     56                  setime(0, 0);
  458.     57                  distance("dz", 100.);
  459.     58                  move(p2);
  460.     59                  move(p2);
  461.     60
  462.     61                  waitfor(p1->end)
  463.     62                  printf("guarded motion 1 starts\\\\n");
  464.     63                  waitfor(p1->end)
  465.     64                  if (p1->code == TOUCHED)
  466.     65                          printf("touched\\\\n");
  467.     66                  else
  468.     67                          printf("not touched\\\\n");
  469.     68
  470.     69                  waitfor(p2->end)
  471.     70                  printf("guarded motion 2 starts\\\\n");
  472.     71                  waitfor(p2->end)
  473.     72                  if (p2->code == TOUCHED)
  474.     73                          printf("touched\\\\n");
  475.     74                  else
  476.     75                          printf("not touched\\\\n");
  477.     76
  478.     77                  printf("more ? ");
  479.     78                  QUERY(q); if (q == 'n') break;
  480.     79          }
  481.     80          setvel(300, 100);
  482.     81          move(park);
  483.     82          waitfor(completed);
  484.     83          OPEN;
  485.     84  }
  486.     85
  487.     86
  488.     87  touchfn()
  489.     88  {
  490.     89          if (how.adcr[sensor] > 1) {
  491.     90                  nextmove = TOUCHED;
  492.     91          }
  493.     92  }
  494. .DE
  495. .cs R
  496. .PP
  497. We are now familiar with lines 1 and 2.
  498. Line 3 includes the real time interface declarations [6], in order
  499. to gain access to the analog conversions.
  500. Line 4 includes the file
  501. .B umac.h
  502. that contains a set of useful macros (see include files),
  503. among them we shall use
  504. the macro `QUERY' that causes the prompt `` (y/n) '' to be printed on the termin
  505. and will return when the user has typed a `y' or a `n'.
  506. The typed character is then returned in the macro's argument.
  507. Line 6 declares the type of the array in which we get the analog readings.
  508. Line 8 allocates an integer that will be the index in the array `adcr'
  509. of the readings of the opened analog channel.
  510. Line 10 defines the return code of the guarded motion.
  511. Let us skip the transforms and position initializations that
  512. do not show anything special.
  513. With a combination of queries we ask the operator to place
  514. the sensor in the gripper's jaws and to command the gripper to close.
  515. We leave to the operator the option of canceling the task on line 39
  516. if something goes wrong.
  517. Line 43 allocates analog channel number 7 to the sensor.
  518. In the body of the loop, lines 45 to 78, the manipulator performs two
  519. guarded motions : moves to a position next to an expected obstacle,
  520. moves along the Z direction in the
  521. .I tool
  522. frame, while evaluating at sample intervals the monitoring function `touchfn'.
  523. The call to
  524. .B setime
  525. specifies a zero transition time at the end of the motion in order to
  526. obtain a fast reaction time.
  527. The null transition time can be specified here as we have made sure
  528. that the velocities are small.
  529. We also make sure that the motion queue contains a position
  530. such as the arm will back up when the obstacle in encountered.
  531. This is the purpose of the move statements lines 52 and 59.
  532. .PP
  533. Using the
  534. .B waitfor
  535. macro, the program can print information
  536. at the terminal as the task proceeds.
  537. In particular, it is possible to decided if the guarded motion
  538. did encounter an obstacle.
  539. The value `TOUCHED' is returned in the `code' part of the positions if
  540. the monitoring function caused a motion interruption, otherwise
  541. the value `OK' is returned.
  542. The monitoring function, lines 86 to 91, checks the analog conversion
  543. reading and sets the flag
  544. .B nextmove
  545. when appropriate.
  546. .PP
  547. Some other combinations are possible, as shown by the following
  548. code patterns :
  549. .br
  550. .cs R 23
  551. .DS L
  552.         move(p);
  553.         evalfn(monitorfn);
  554.         setime(100, 10000);
  555.         move(p);
  556.         waitfor(completed)
  557.         if (p->code != EXPECTED) {
  558.                 printf("timeout after 10 seconds\\\\n");
  559.                 error();
  560.         }
  561.         move(p1);
  562. .DE
  563. .cs R
  564. causes the arm to stop at the position `p' while evaluating a monitor
  565. function, and the motion to resume on condition.
  566. It is not possible to use a
  567. .B stop
  568. statement here, since
  569. .B stop
  570. keeps all the attributes of the previous motion and we need to specify
  571. a new
  572. .B move
  573. request.
  574. The sequence of code :
  575. .br
  576. .cs R 23
  577. .DS L
  578.         evalfn(monitorfn);
  579.         move(p);
  580.         stop(1000);
  581.         move(p);
  582. .DE
  583. .cs R
  584. does not causes a motion to be interrupted for one second, unless
  585. the position `p' has been reached when the
  586. .B stop
  587. request is executed because it is equivalent to a new motion to the last
  588. position.
  589. Similarly, one must be careful that the
  590. .B stop
  591. statement does not necessarily mean that the manipulator will
  592. stop in absolute coordinates if the position equation for `p' contains
  593. moving coordinate frames.
  594. When an absolute stop is needed or when a motion has to stop
  595. and the manipulator has to remain exactly at the position where
  596. it stopped, RCCL provides a built-in position equation of the
  597. following form :
  598. .EQ
  599. ~T6~=~HERE
  600. .EN
  601. where $HERE$ is a transform internally maintained by the system
  602. to be always equal to $T6$ at the end of any path segment.
  603. At startup time, the system issues the following call :
  604. .br
  605. .cs R 23
  606. .DS L
  607.         there = makeposition("THERE", t6, EQ, here, TL, t6);
  608. .DE
  609. .cs R
  610. to implement this feature, where
  611. .B here
  612. is of type TRSF_PTR and
  613. .B there
  614. of type POS_PTR.
  615. The following code pattern shows how we can use the fact that
  616. the flag
  617. .B nextmove
  618. can be set from the user's process to implement a stop on terminal input :
  619. .br
  620. .cs R 23
  621. .DS L
  622.         move(p);
  623.         move(there);
  624.         printf("hit return to interrupt motion ");
  625.         getchar();
  626.         nextmove = YES;
  627. .DE
  628. .cs R
  629. When `return' is hit, the system interrupts the motion toward `p',
  630. and starts a transition to the position `there' that causes the arm to over
  631. shoot by a magnitude as great as the velocity was high.
  632. When the velocity is small and a sharp stop is needed we can write :
  633. .br
  634. .cs R 23
  635. .DS L
  636.         move(p);
  637.         setime(0, 0);
  638.         move(there);
  639.         printf("hit return to interrupt motion ");
  640.         getchar();
  641.         nextmove = YES;
  642. .DE
  643. .cs R
  644. In the same way monitoring can achieved with :
  645. .br
  646. .cs R 23
  647. .DS L
  648.         move(p);
  649.         waitas(goalpos == p)
  650.         p->end = 1;                     /* preset event */
  651.         while(p->end) {
  652.                 if (condition) {
  653.                         nextmove = YES;
  654.                 }
  655.                 suspendfg();
  656.         }
  657. .DE
  658. .cs R
  659. This way of coding can be useful in the cases when
  660. it is not possible to place the condition calculations in the
  661. background function.
  662. .PP
  663. RCCL internally monitors if the joint physical limits are
  664. going to be reached (within a few degrees for each joint).
  665. If such an error condition occurs, the system automatically
  666. issues a move to the `there' position, that causes an immediate stop
  667. next to the limit position and returns the code `LIMIT'
  668. for the motion that caused the error condition.
  669. A new motion is then taken out of queue and the error condition
  670. is reset.
  671. If the new motion persists in causing a joint limit error, the whole
  672. task will abort.
  673. If motions are likely to cause such joint limit errors,
  674. the returned codes should be checked and the appropriate action
  675. undertaken.
  676. .NH 2
  677. Tracking
  678. .PP
  679. Tracking is obtained by synchronously updating functionally defined
  680. transforms from sensor readings.
  681. All the examples given in the section ``Functionally defined motions''
  682. would become examples for tracking motions if we would replace the
  683. parameter `time' by some sensor readings reflecting the position
  684. of the moving coordinate frames.
  685. We shall however explain yet another example using the simple
  686. potentiometer based position sensor introduced in the previous section.
  687. The sensor, placed in the
  688. .I tool
  689. frame, allows the manipulator to track an arbitrary surface intersecting
  690. the Z axis of the tool frame.
  691. The tracking function is written in such a way that it causes the
  692. motion velocity to be proportional to the distance the shaft of the linear
  693. potentiometer
  694. is protruding out of the sensor.
  695. A velocity control of the manipulator
  696. end effector is implemented such as that the shaft is partially inside the
  697. body of the sensor, the velocity along the Z axis
  698. of the
  699. .I tool
  700. frame is controlled to be zero.
  701. .br
  702. .cs R 23
  703. .DS L
  704.      1  #include "rccl.h"
  705.      2  #include "rtc.h"
  706.      3  #include "umac.h"
  707.      4
  708.      5  extern struct how how;
  709.      6
  710.      7  int sensor;
  711.      8
  712.      9  pumatask()
  713.     10  {
  714.     11          TRSF_PTR z, b1, b2, fing, fins, over;
  715.     12          POS_PTR  p1, p2, get;
  716.     13          int fingfn();
  717.     14          int q;
  718.     15
  719.     16          fing = newtrans("FING",fingfn);
  720.     17          Rot(fing, zunit, -90.);
  721.     18          fins = gentr_rot("FINS", 0., 0., 0., zunit, -90.);
  722.     19          z = gentr_rot("Z",  0.,  0., 864., zunit, 0.);
  723.     20          b1 = gentr_rot("B1", 600. ,-300., 450., yunit, 180.);
  724.     21          b2 = gentr_rot("B2", 600. , 300., 450., yunit, 180.);
  725.     22          over = gentr_rot("OVER", 600., 0., 600., yunit, 180.);
  726.     23
  727.     24          p1 = makeposition("P1" , z, t6, fins, EQ, b1, TL, fins);
  728.     25          p2 = makeposition("P2" , z, t6, fing, EQ, b2, TL, fing);
  729.     26          get = makeposition("GET", z, t6, EQ, over, TL, t6);
  730.     27
  731.     28
  732.     29          sensor = adcopen(7);
  733.     30
  734.     31          setmod('c');
  735.     32          for (; ; ) {
  736.     33                  setvel(400, 300);
  737.     34                  move(get);
  738.     35                  move(p1);
  739.     36                  setvel(100, 100);
  740.     37                  sample(15);
  741.     38                  move(p2);
  742.     39                  sample(30);
  743.     40                  printf("more ?"); QUERY(q); if (q == 'n') break;
  744.     41          }
  745.     42          setvel(400, 300);
  746.     43          setmod('j');
  747.     44          move(park);
  748.     45  }
  749.     46
  750.     47
  751.     48
  752.     49  fingfn(t)
  753.     50  TRSF_PTR t;
  754.     51  {
  755.     52          t->p.z += (how.adcr[sensor] * .01 - 3.) / 3.;
  756.     53  }
  757. .DE
  758. .cs R
  759. .PP
  760. This example uses three positions equations.
  761. The position P1 from where the tracking motion begins, uses
  762. a $TOOL$ transform FINS set as a translation and a rotation
  763. such as to present the sensor with a proper angle.
  764. The position P2 is the end of the tracking motion, the
  765. $TOOL$ transform FING is initialized to be equal to FINS.
  766. However, as the motion progresses, its $p sub z$ element will
  767. be changed by the function `fingfn' in order modify
  768. the trajectory in the desired direction.
  769. The function `fingfn', lines 49 to 53, implements the control law whose
  770. parameters have been experimently determined, in terms of a gain
  771. and an offset.
  772. The sample rate is set at a higher value during the tracking
  773. motion in order to obtain a faster response.
  774. .PP
  775. An interresting variation of this program would be
  776. to record the value of $T6$ as the tracking proceeds.
  777. Since it is not possible to perform any input-output
  778. from a background function, a buffer alternating technique
  779. would need to be implemented : while the background function fills
  780. one buffer, the user's foreground process could dump another one on file.
  781. It would then become possible to replay very long motion sequences,
  782. as they have been recorded or in such a way that the
  783. .I tool
  784. frame would have a fixed angle with respect to the tracking
  785. trajectory as required in welding applications (Section ``Functionally
  786. defined motions'', example 4).
  787. .PP
  788. When the sensory input is too slow or when computations are too lengthy
  789. to be performed in a background function (10 ms cpu time every 28 ms
  790. would really tie the machine down), a pseudo tracking can be obtained
  791. by using an asynchronous loop in the user's process updating a
  792. .I varb
  793. type transform.
  794. For example :
  795. .br
  796. .cs R 23
  797. .DS L
  798.         TRSF_PTR z, e, b, r;
  799.         POS_PTR p0, p1, ... , pt;
  800.         TRSF changes;
  801.  
  802.         z = ...
  803.         e = ...
  804.         b = ...
  805.         r = ...
  806.         upd = newtrans("UPD", varb);
  807.  
  808.         p0 = makeposition(...);
  809.         p1 = makeposition(...);
  810.         pt = makeposition("P", z, t6, e, EQ, b, upd, r, TL, e);
  811.  
  812.         ...
  813.  
  814.         move(p0);
  815.         move(p1);
  816.         move(pt);
  817.  
  818.         waitas(goalpos == pt)
  819.         while(goalpos == pt) {
  820.                 getsensor(&changes);
  821.                 Trmultinp(upd, &changes);
  822.                 suspendfg();
  823.         }
  824.         ....
  825. .DE
  826. .cs R
  827. .PP
  828. The function `getsensor' returns alterations to be performed on the
  829. transform $UPD$, that are accumulated by successive multiplications.
  830. The function
  831. .B suspendfg
  832. is used to allow the machine to ``breath''.
  833. The changes should not cause more than a few millimeters or degrees position
  834. steps at the end effector.
  835. .PP
  836. Another way to obtain this type of tracking is to use very short motions and
  837. to synchronize them with the sensory input.
  838. We can take advantage of the fact that no time is spend for parsing
  839. the
  840. .B move
  841. instructions and the motions can be very short.
  842. We will preferably
  843. use the
  844. .I joint
  845. mode because it requires far less computations and the path approximation
  846. remains good if the path segments are small.
  847. As opposed to the previous method, we need to use a
  848. .I hold
  849. transform to keep track of all the successive values.
  850. The
  851. .I hold
  852. transforms have also the property of being retained by the system
  853. from one path to another for the transition calculations.
  854. The code pattern may look like :
  855. .br
  856. .cs R 23
  857. .DS L
  858.         ...
  859.         upd = newtrans("UPD", hold);
  860.         ...
  861.  
  862.         move(pt);
  863.         waitfor(completed);
  864.         setmod('j');
  865.         rtime = 0;
  866.         while (rtime < tracktime) (
  867.                 getsensor(&changes);
  868.                 Trmultinp(upd, &changes);
  869.                 move(pt);
  870.                 waitas(nbrequest < 2);
  871.         }
  872. .DE
  873. .cs R
  874. At the end of the loop, the
  875. .B waitas
  876. primitive allows the loop to proceed an perform another sensorial input
  877. while the arm is still moving.
  878. A look ahead is thus implemented although
  879. it may lead to an unstable control.
  880. If the loop is strongly synchronized by a `waitas(nbrequest < 1)',
  881. the manipulator will stop at each loop before proceeding.
  882. Since the successive motions are expected to be small, we
  883. can afford to suppress of the transitions by a call to `setime(0, 0)'.
  884. In the above examples, we have implemented the tracking in terms of
  885. .B changes
  886. with respect to the current position.
  887. In other words, we assume that the sensor is linked with the
  888. manipulator and that the changes to be performed represent the tracking
  889. error.
  890. .PP
  891. Guarded motions can also be implemented using a similar technique :
  892. .br
  893. .cs R 23
  894. .DS L
  895.         setmod('j');
  896.         while (getsensor() == goahead) {
  897.                 Trmulinp(upd, &step);
  898.                 setime(0, 0);
  899.                 move(pt);
  900.                 waitfor(pt->end);
  901.         }
  902. .DE
  903. .cs R
  904. .PP
  905. According to the situation, different path segment times
  906. or velocities
  907. as well as strategies can to be experimented.
  908. .NH 2
  909. Updating the World Model
  910. .PP
  911. For all motions terminated on a condition, keeping track of
  912. the position where the manipulator stopped is another way
  913. of acquiring information from the environment.
  914. Instead of merely recording the position of the manipulator,
  915. the
  916. .B update
  917. primitive allows the user to record positions in a structured manner.
  918. The
  919. .B update
  920. function takes two arguments, a transform pointer, and a position
  921. equation pointer :
  922. .br
  923. .cs R 23
  924. .DS L
  925.         update(trans, pos)
  926.         TRSF_PTR trans;
  927.         POS_PTR pos;
  928. .DE
  929. .cs R
  930. The
  931. .B update
  932. function causes the position equation `pos'
  933. to be solved for the transform `trans',
  934. using the value of $T6$ at the end of the corresponding path segment.
  935. Of course, the transform must belong to the position equation.
  936. The transform must also be of type
  937. .I varb.
  938. The second argument, a position equation pointer, is not necessarily
  939. the same argument as the one of the corresponding motion statement.
  940. For example, we can update a transform on user request :
  941. .br
  942. .cs R 23
  943. .DS L
  944.         a = gentr...
  945.         e = gentr...
  946.         y = gentr...
  947.         z = gentr...
  948.  
  949.         x = newtrans("X", varb);
  950.  
  951.         p1 = makeposition("P1", z, t6, e, EQ, a, TL, e);
  952.         p2 = makeposition("P2", z, t6, e, EQ, x, y, TL, e);
  953.  
  954.         ...
  955.  
  956.         update(x, p2);
  957.         move(p1);
  958.         move(p2);
  959.         printf("hit return to interrupt motion ");
  960.         getchar();
  961.         nextmove = YES;
  962. .DE
  963. .cs R
  964. An update request is associated with position P1.
  965. When the user hits `return', the motion toward P1 is interrupted and
  966. the transform X is solved as :
  967. .EQ
  968. X~=~Z~T6~E~Y sup -1
  969. .EN
  970. and the position P2 corresponds exactly to the position the manipulator
  971. was and a stop is obtained.
  972. Subsequent motions to this position are therefore possible.
  973. The transform X can also be used in other position equations.
  974. One must notice that all the positions containing X are consequently changed.
  975. This leads to
  976. numerous applications of
  977. .B update.
  978. .bp
  979. .NH
  980. Force Control
  981. .PP
  982. In assembly tasks, objects are required to be brought into contact,
  983. and motions have to be stopped when the collision occurs.
  984. Once objects are in contact the task is said to be constrained
  985. because arbitrary motions are no longer possible in every direction.
  986. The notion of guarded motion has been introduced earlier and
  987. force guarded motions are quite similar.
  988. The force monitoring function is built into the system
  989. considering that it is somewhat dependent on the installation and
  990. that force specifications are really an integral part of a motion
  991. description.
  992. Force specifications are transmitted to the background process via
  993. the
  994. .B limit
  995. primitive.
  996. When the task is constrained, the arm is requested to exert
  997. forces on objects and is no longer position servoed for
  998. each of the six degrees of freedom.
  999. Depending on the geometry of the task, one or several directions
  1000. are selected to provide for compliance.
  1001. The arm is then said to enter a
  1002. .I comply
  1003. mode which is specified by the
  1004. .B comply
  1005. primitive.
  1006. When the contact between objects ceases,
  1007. or when constraints disappear,
  1008. the arm has to gain back position servoed directions.
  1009. This is achieved by the
  1010. .B lock
  1011. primitive.
  1012. The cessation of contact can be detected by
  1013. differential motions of the arm when the constraints disappear.
  1014. The primitive
  1015. .B limit
  1016. is also used for this purpose.
  1017. .NH 2
  1018. Stop, Go on Force, on Displacement
  1019. .PP
  1020. As we have seen before, stop and go are not essentially different, they
  1021. both correspond to the interruption of a motion.
  1022. When a limit condition is specified, a monitor function is internally
  1023. activated for the subsequent motion.
  1024. The form of
  1025. .B limit
  1026. is :
  1027. .br
  1028. .cs R 23
  1029. .DS L
  1030.         limit(dirs, value [, value] ...)
  1031.         char *dirs;
  1032.         double value;
  1033. .DE
  1034. .cs R
  1035. The limit directions specifications are expressed in the string
  1036. first argument with a combination of the following, separated by one
  1037. or several spaces :
  1038. .br
  1039. .cs R 23
  1040. .DS L
  1041.         fx fy fz : force         along X Y Z
  1042.         tx ty tz : torque        about X Y Z
  1043.         dx dy dz : displacement  along X Y Z
  1044.         rx ry rz : rotation      about X Y Z
  1045. .DE
  1046. .cs R
  1047. All limit specifications are expressed in the
  1048. .I tool
  1049. frame of the corresponding position equation and
  1050. take effect for the subsequent
  1051. .I move
  1052. request.
  1053. To each direction specification must correspond a value, for example :
  1054. .br
  1055. .cs R 23
  1056. .DS L
  1057.         limit("fx tz", 10., 5.);
  1058. .DE
  1059. .cs R
  1060. will request a force of 10
  1061. .B Newtons
  1062. along X, and of a torque 5.
  1063. .B Newton-meter
  1064. about Z to be monitored.
  1065. When either of the specifications
  1066. is exceeded, the corresponding motion is interrupted
  1067. and the task proceeds with the next request in the motion queue.
  1068. The `code' field of the corresponding position is set to `ONF'.
  1069. Likewise, distance specifications can be coded as :
  1070. .br
  1071. .cs R 23
  1072. .DS L
  1073.         limit("dx ry", 3., 1.);
  1074. .DE
  1075. .cs R
  1076. that causes the motion to be interrupted when the distance
  1077. change along X exceeds 3
  1078. .B millimeters
  1079. or when the rotations about Y exceeds 1
  1080. .B degree.
  1081. Only absolute values of the limit specifications are taken into account.
  1082. .NH 2
  1083. Servo Modes, Comply and Lock
  1084. .PP
  1085. A comply servo mode is requested via the
  1086. .B comply
  1087. primitive according to the following format :
  1088. .br
  1089. .cs R 23
  1090. .DS L
  1091.         comply(dirs, value [, value] ...)
  1092.         char *dirs;
  1093.         double value;
  1094. .DE
  1095. .cs R
  1096. The
  1097. .B comply
  1098. primitive causes the subsequent motion request to
  1099. be executed such that forces and/or torques are maintained in the
  1100. .I tool
  1101. frame instead of positions and/or rotations.
  1102. The arm then enters the specified
  1103. .I comply
  1104. mode in the corresponding motion and all the following motions until
  1105. the
  1106. .B lock
  1107. primitive brings the manipulator back into position servo mode for
  1108. the selected directions.
  1109. The format for
  1110. .B lock
  1111. is :
  1112. .br
  1113. .cs R 23
  1114. .DS L
  1115.         lock(dirs)
  1116.         char *dirs;
  1117. .DE
  1118. .cs R
  1119. .PP
  1120. The first argument of
  1121. .B comply
  1122. and
  1123. .B lock
  1124. is a string containing direction specifications made up of
  1125. a combination of the following :
  1126. .br
  1127. .cs R 23
  1128. .DS L
  1129.         fx fy fz : force  along X Y Z
  1130.         tx ty tz : torque about X Y Z
  1131. .DE
  1132. .cs R
  1133. .PP
  1134. The second argument of
  1135. .B comply
  1136. is the signed magnitude of the desired forces and/or torques.
  1137. .PP
  1138. Care must be taken that the sequence of servo mode specification is
  1139. consistent.
  1140. Requiring the arm to comply along or about a direction already in
  1141. .I comply
  1142. servo mode or locking a direction not in
  1143. .I comply
  1144. servo mode will cause an error.
  1145. In order to keep track of the different specifications, line
  1146. indentation is advised :
  1147. .br
  1148. .cs R 23
  1149. .DS L
  1150.         move(p0);
  1151.         comply("dy", 0.);
  1152.                 move(p1);
  1153.                 move(p2);
  1154.                 comply("dx ry", 5., 3.);
  1155.                                 move(p3);
  1156.                         lock("ry");
  1157.                         move(p4);
  1158.                         move(p5);
  1159.                 lock("dx");
  1160.                 move(p6);
  1161.         lock("dy");
  1162.         move(p7);
  1163. .DE
  1164. .cs R
  1165. .PP
  1166. Either
  1167. .I Cartesian
  1168. or
  1169. .I joint
  1170. motion modes can used for complying motion sequences.
  1171. However, they behave differently.
  1172. In
  1173. .I Cartesian
  1174. mode, the system automatically compensate for position errors due to
  1175. unwanted accommodating joint motions [2].
  1176. In
  1177. .I joint
  1178. mode, there is no compensation.
  1179. .NH 2
  1180. Carrying Loads
  1181. .PP
  1182. The function
  1183. .B massis
  1184. allows the user to specify that a mass is to be carried by the manipulator.
  1185. The mass of the object, expressed in kilograms, causes the system
  1186. to compute gravity compensation terms in the motions using
  1187. force control.
  1188. The mass of object is initially set to 0. and can be set or
  1189. reset via
  1190. .B massis :
  1191. .br
  1192. .cs R 23
  1193. .DS L
  1194.         massis(mass)
  1195.         double mass;
  1196. .DE
  1197. .cs R
  1198. As usual, the new value is taken into account the next motion request.
  1199. .NH 2
  1200. Examples
  1201. .PP
  1202. .B
  1203. 1)
  1204. .R
  1205. The first example involves a solid horizontal surface.
  1206. The manipulator is programmed to reach to the table
  1207. in a motion normal to the expected surface.
  1208. It then enters the
  1209. .I comply
  1210. mode in order to slide along.
  1211. During the second sliding motion, it detects an edge of the surface by
  1212. exerting a preload force and monitoring the position changes in the
  1213. Z direction of the
  1214. .I tool
  1215. frame.
  1216. .br
  1217. .cs R 23
  1218. .DS L
  1219.      1  #include "rccl.h"
  1220.      2  #include "umac.h"
  1221.      3
  1222.      4  pumatask()
  1223.      5  {
  1224.      6          TRSF_PTR z, e , b1, b2, b3, b4, b5;
  1225.      7          POS_PTR  p1, p2, p3, p4, p5;
  1226.      8          int q;
  1227.      9
  1228.     10          z = gentr_trsl("Z",  0.,  0., 864.);
  1229.     11          e = gentr_trsl("E" , 0. , 0. , 170.);
  1230.     12          b1 = gentr_rot("B1", 600. ,-100.,  300., yunit, 180.);
  1231.     13          b2 = gentr_rot("B2", 600. , 200.,  300., yunit, 180.);
  1232.     14          b3 = gentr_rot("B3", 600. , 200.,  400., yunit, 180.);
  1233.     15          b4 = gentr_rot("B4", 600. ,-100.,  400., yunit, 180.);
  1234.     16          b5 = gentr_rot("B5", 500. ,-100.,  300., yunit, 180.);
  1235.     17
  1236.     18          p1   = makeposition("P1" , z, t6, e, EQ, b1, TL, e);
  1237.     19          p2   = makeposition("P2" , z, t6, e, EQ, b2, TL, e);
  1238.     20          p3   = makeposition("P3" , z, t6, e, EQ, b3, TL, e);
  1239.     21          p4   = makeposition("P4" , z, t6, e, EQ, b4, TL, e);
  1240.     22          p5   = makeposition("P5" , z, t6, e, EQ, b5, TL, e);
  1241.     23
  1242.     24
  1243. .DE
  1244. .cs R
  1245. .br
  1246. .cs R 23
  1247. .DS L
  1248.     25          setmod('c');
  1249.     26          setvel(200, 100);
  1250.     27          move(p4);
  1251.     28          for (; ; ) {
  1252.     29                  QUERY(q); if (q == 'n') break;
  1253.     30
  1254.     31                  p1->end = 0;
  1255.     32
  1256.     33                  setvel(20, 20);
  1257.     34                  limit("fz", 20.);
  1258.     35                  move(p1);
  1259.     36
  1260.     37                  setvel(100, 50);
  1261.     38                  comply("fz", 10.);
  1262.     39                          move(p2);
  1263.     40                  lock("fz");
  1264.     41
  1265.     42
  1266.     43                  waitfor(p1->end);
  1267.     44                  if (p1->code != ONF) {
  1268.     45                          nextmove = YES;
  1269.     46                          printf("where is the table ?\\\\n");
  1270.     47                          setvel(200, 100);
  1271.     48                          move (park);
  1272.     49                          return;
  1273.     50                  }
  1274.     51
  1275.     52                  move(p3);
  1276.     53                  move(p4);
  1277.     54
  1278.     55                  limit("fz", 20.);
  1279.     56                  setvel(50, 50);
  1280.     57                  move(p1);
  1281.     58
  1282.     59                  limit("dz", 3.);
  1283.     60                  comply("fz", 10.);
  1284.     61                          move(p5);
  1285.     62                  lock("fz");
  1286.     63
  1287.     64                  move(p4);
  1288.     65
  1289.     66                  waitfor(p5->end);
  1290.     67                  if (p5->code != OND) {
  1291.     68                          printf("where is the edge ?\\\\n");
  1292.     69                  }
  1293.     70          }
  1294.     71          setvel(300, 50);
  1295.     72          move(park);
  1296.     73  }
  1297. .DE
  1298. .cs R
  1299. .PP
  1300. The transforms and positions define a set of five position
  1301. next to the surface.
  1302. The surface if assumed to be less than 100 millimeters below the
  1303. position P4, such that a collision should occur when moving from
  1304. P4 to P1, located 100 millimeter below P4.
  1305. Position P3 is at the same level than P4 and above P2.
  1306. Position P5 is assumed to bring the end effector off the
  1307. boundaries of the table, when moving from P1 to P5.
  1308. As we may have more motions toward P1 that waits for the end of motion,
  1309. the `p1->end' event is reset for each loop line 31.
  1310. Lines 33 to 40, implement a sequence of motion requests so as
  1311. to program the manipulator to enter the
  1312. .I comply
  1313. when the obstacle in encountered.
  1314. Lines 43 through 50, we make sure that the limit have actually
  1315. been met, otherwise the motion toward P2 is canceled as well as the task.
  1316. In the normal case, lines 52 and 53 bring the arm back above the surface.
  1317. The same guarded motion is then performed toward P1, but now
  1318. the motion in
  1319. .I comply
  1320. servo mode is performed toward P5 where the edge of the surface is
  1321. expected to be found.
  1322. The termination of this last motion is also checked at lines 66 through 69.
  1323. A preload force in the Z direction
  1324. is applied for all motions to make sure that
  1325. the contact is maintained.
  1326. .bp
  1327. .PP
  1328. .B
  1329. 2)
  1330. .R
  1331. In this second example, the manipulator is programmed for the task of
  1332. turning a crank.
  1333. Two compliant directions are required in this operation.
  1334. During the compliant motion, the
  1335. .I tool
  1336. frame rotates so as to keep a constant
  1337. orientation with respect to the crank handle.
  1338. We define the compliant directions with respect to this frame.
  1339. A grasp position is also defined to allow for some clearance.
  1340. The task will turn the crank a given number of times.
  1341. One turn is programmed to last 4 seconds.
  1342. .br
  1343. .cs R 23
  1344. .DS L
  1345.      1  #include "rccl.h"
  1346.      2  #include "umac.h"
  1347.      3  #include "hand.h"
  1348.      4
  1349.      5  int turns;
  1350.      6
  1351.      7  pumatask()
  1352.      8  {
  1353.      9          TRSF_PTR z, e, shaft, handle, apro, grasp, rotpx, rotnx;
  1354.     10          POS_PTR  get, away;
  1355.     11          POS_PTR turn;
  1356.     12          int pxfn(), nxfn();
  1357.     13          int q;
  1358.     14
  1359.     15          rotpx = newtrans("ROTPX", pxfn);
  1360.     16          rotnx = newtrans("ROTNX", nxfn);
  1361.     17          z = gentr_trsl("Z",  0.,  0., 864.);
  1362.     18          e = gentr_trsl("E" , 0. , 0. , 170.);
  1363.     19          shaft = gentr_trsl("SHAFT", -200., 500., 600.);
  1364.     20          shaft->fn = varb;
  1365.     21          handle = gentr_trsl("HANDLE", 0., 0., 50.);
  1366.     22          apro = gentr_trsl("APRO", -50., 0., 0.);
  1367.     23          grasp = gentr_rpy("GRASP", 0., 0., 0., 0., 190., 0.);
  1368.     24
  1369.     25          get = makeposition(
  1370.     26          "GET", z, t6, e, EQ, shaft, handle, grasp, TL, e);
  1371.     27
  1372.     28          away = makeposition(
  1373.     29          "AWAY", z, t6, e, EQ, shaft, handle, grasp, apro, TL, e);
  1374.     30
  1375.     31          turn = makeposition(
  1376.     32          "TURN", z, t6, e, EQ, shaft, rotpx, handle, rotnx, grasp, TL, ro
  1377.     33
  1378.     34          setvel(300, 300);
  1379.     35          move(away);
  1380.     36          OPEN;
  1381.     37          if (!teach(shaft, get)) {
  1382.     38                  move(away);
  1383.     39                  move(park);
  1384.     40                  return;
  1385.     41          }
  1386. .DE
  1387. .cs R
  1388. .br
  1389. .cs R 23
  1390. .DS L
  1391.     42          shaft->fn = const;
  1392.     43          optimize(turn);
  1393.     44          turns = 4;
  1394.     45          waitfor(completed);
  1395.     46          CLOSE;
  1396.     47          comply("fx fz ", 0., 0.);
  1397.     48                  movecart(turn, 200, 4000 * turns);
  1398.     49          lock("fx fz ");
  1399.     50          move(get);
  1400.     51          waitfor(turn->end);
  1401.     52          OPEN;
  1402.     53          distance("dx", -30.);
  1403.     54                  move(get);
  1404.     55          setvel(200, 50);
  1405.     56          setmod('j');
  1406.     57          move(park);
  1407.     58  }
  1408.     59
  1409.     60  pxfn(t)
  1410.     61  TRSF_PTR t;
  1411.     62  {
  1412.     63          Rot(t, xunit, goalpos->scal * 360 * turns);
  1413.     64  }
  1414.     65
  1415.     66  nxfn(t)
  1416.     67  TRSF_PTR t;
  1417.     68  {
  1418.     69          Rot(t, xunit, - goalpos->scal * 360 * turns);
  1419.     70  }
  1420. .DE
  1421. .cs R
  1422. .PP
  1423. The manipulator is first moved to a safe position away from
  1424. obstacles.
  1425. Lines 37 to 41, the manual teach mode built in RCCL is called.
  1426. This teach mode makes use of the
  1427. .B update
  1428. function to record a position.
  1429. That is why the transform $SHAFT$ is first declared as a
  1430. .I varb
  1431. transform.
  1432. Once this transform is taught, its type can be changed, line 42, and the
  1433. position $TURN$ optimized line 43.
  1434. Gripper actions are obtained as usual.
  1435. Once these preliminary operations are performed, the turning motion
  1436. can begin.
  1437. It is obtained in terms of a functionally defined motion, line 48,
  1438. executed in
  1439. .I comply
  1440. servo mode.
  1441. The duration of the motion is the number of turns times four seconds.
  1442. Care has been taken line 32, such that the compliance frame is
  1443. properly specified.
  1444. .bp
  1445. .PP
  1446. .B
  1447. 3)
  1448. .R
  1449. The third example illustrates the peg in a hole insertion task.
  1450. The strategy consists of moving toward the expected location of
  1451. the hole with a small approach angle.
  1452. Even with a poor position accuracy the end of the peg will enter
  1453. the hole with a high degree of confidence.
  1454. As soon as a collision occurs, the manipulator is programmed to
  1455. go in
  1456. .I comply
  1457. mode in the Z direction with a preload force in the same direction.
  1458. While complying, the peg is rotated so as to be aligned with the axis of
  1459. the hole.
  1460. The manipulator is then programmed to comply in the normal directions
  1461. of the hole axis and
  1462. a motion inside the hole is immediately started.
  1463. The presence of a small chamfer helps the peg not to slip off the
  1464. initial insertion position.
  1465. The force in Z is also limited since the insertion may jam
  1466. due to a misalignment.
  1467. The fit is not very tight, and we can expect that a
  1468. portion of the peg is inserted before the jam occurs.
  1469. A sequence of four accommodation rotating motions
  1470. using
  1471. .B update,
  1472. allows the
  1473. manipulator to ``feel'' the walls of the hole and to record a correct alignment.
  1474. In a final effort, the peg is inserted all the way.
  1475. Finally, the peg is pulled out with no difficulty since the alignment
  1476. has been corrected.
  1477. The moment when the task becomes unconstrained  is detected by
  1478. monitoring the differential motions.
  1479. .br
  1480. .cs R 23
  1481. .DS L
  1482.      1  #include "rccl.h"
  1483.      2  #include "umac.h"
  1484.      3  #include "hand.h"
  1485.      4
  1486.      5  pumatask()
  1487.      6  {
  1488.      7          TRSF_PTR z, e, peg, hole, roty, bottom, angle;
  1489.      8          POS_PTR align, in, touch;
  1490.      9          int q;
  1491.     10
  1492.     11          z = gentr_trsl("Z",  0.,  0., 864.);
  1493.     12          e = gentr_trsl("E" , 0. , 0. , 140.);
  1494.     13          peg = gentr_trsl("PEG", 0., 0., 10.);
  1495.     14          hole = gentr_trsl("HOLE", -50., 450., 500.);
  1496.     15          hole->fn = varb;
  1497.     16          bottom = gentr_trsl("BOTTOM", 0., 0., -20.);
  1498.     17          roty = gentr_rot("ROTY", 0., 0., 0., yunit, 180.);
  1499.     18          angle = gentr_rot("ANGLE", 0., 0., 0., yunit, 12.);
  1500.     19
  1501.     20          align = makeposition(
  1502.     21          "ALIGN", z, t6, e, peg, EQ, hole, roty, TL, peg);
  1503.     22
  1504.     23          touch = makeposition(
  1505.     24          "TOUCH", z, t6, e, peg, EQ, hole, angle, roty, TL, peg);
  1506.     25
  1507.     26          in = makeposition(
  1508.     27          "IN", z, t6, e, peg, EQ, hole, bottom, roty, TL, peg);
  1509.     28
  1510.     29          setvel(300, 50);
  1511.     30          move(align);
  1512.     31          if (!teach(hole, align)) {
  1513.     32                  setvel(300, 50);
  1514.     33
  1515.     34                  distance("dz", -100.);
  1516.     35                          move(align);
  1517.     36
  1518.     37                  setmod('j');
  1519.     38                  move(park);
  1520.     39                  return;
  1521.     40          }
  1522.     41          setmod('c');
  1523.     42          setvel(100, 100);
  1524.     43
  1525.     44          distance("dz", -10.);
  1526.     45                  move(touch);
  1527.     46
  1528.     47          QUERY(q);
  1529.     48
  1530.     49          if (q == 'n') {
  1531.     50                  setvel(300, 100);
  1532.     51                  setmod('j');
  1533.     52                  move(park);
  1534.     53                  return;
  1535.     54          }
  1536. .DE
  1537. .cs R
  1538. .br
  1539. .cs R 23
  1540. .DS L
  1541.     57          setvel(4, 7);
  1542.     58          distance("dz", -4.);
  1543.     59                  move(touch);
  1544.     60
  1545.     61          limit("fz", 25.);
  1546.     62          distance("dz", 5.);
  1547.     63                  move(touch);
  1548.     64
  1549.     65          comply("fz", 15.);
  1550.     66                  move(align);
  1551.     67          lock("fz");
  1552.     68
  1553.     69          comply("fx fy", 0., 0.);
  1554.     70                  limit("fz", 20.);
  1555.     71                  move(in);
  1556.     72
  1557.     73                  update(hole, in);
  1558.     74                  limit("fz tx", 40., 10.);
  1559.     75                  distance("rx", 2.);
  1560.     76                          move(in);
  1561.     77
  1562.     78                  update(hole, in);
  1563.     79                  limit("fz tx", 40., 10.);
  1564.     80                  distance("rx", -2.);
  1565.     81                          move(in);
  1566.     82
  1567.     83                  update(hole, in);
  1568.     84                  limit("fz ty", 40., 10.);
  1569.     85                  distance("ry", 2.);
  1570.     86                          move(in);
  1571.     87
  1572.     88                  update(hole, in);
  1573.     89                  limit("fz ty", 40., 10.);
  1574.     90                  distance("ry", -2.);
  1575.     91                          move(in);
  1576.     92
  1577.     93                  update(hole, in);
  1578.     94                  limit("fz", 20.);
  1579.     95                  distance("dz", 10.);
  1580.     96                          move(in);
  1581.     97
  1582.     98                  limit("dx dy", 1., 1.);
  1583.     99                  move(align);
  1584.    100          lock("fx fy");
  1585.    101
  1586.    102          setvel(50, 50);
  1587.    103          distance("dz", -50.);
  1588.    104                  move(align);
  1589.    105
  1590.    106          setvel(300, 50);
  1591.    107          setmod('j');
  1592.    108          move(park);
  1593.    109  }
  1594. .DE
  1595. .cs R
  1596. .PP
  1597. The beginning of this task is quite similar to the previous example and
  1598. also makes use of the manual teach mode to record an approximate
  1599. initial position.
  1600. Lines 44 and 45, the manipulator moves to an approach position
  1601. and a chance is given to the user to cancel the task.
  1602. Line 57 to 63, an approach motion and a purposely over shooting motion
  1603. is programmed in order to obtain the initial phase of the insertion
  1604. process.
  1605. While complying and exerting a preloading force the peg is rotated,
  1606. lines 65 to 67, to the aligned position.
  1607. The first insertion attempt is performed line 70 and 71.
  1608. Lines 70 to 91, are programmed the accommodation motions using
  1609. .B update
  1610. to record the successive alignments.
  1611. The final phase of the insertion process is performed lines at 93 to 96.
  1612. The peg is then pulled out of the hole, while monitoring the
  1613. differential motions signaling that the motion becomes unconstrained.
  1614. The peg is then taken away lines 102 to 104.
  1615. .bp
  1616. .PP
  1617. .B
  1618. 4)
  1619. .R
  1620. The last example demonstrates how compliant degrees of freedom
  1621. can be accumulated as constraints are met.
  1622. The manipulator is programmed to detect the walls of a corner and to
  1623. record the position of the corner.
  1624. The program then uses this position information to move the manipulator
  1625. next to the corner within a very small distance.
  1626. .br
  1627. .cs R 23
  1628. .DS L
  1629.      1  #include "rccl.h"
  1630.      2  #include "umac.h"
  1631.      3
  1632.      4  pumatask()
  1633.      5  {
  1634.      6          TRSF_PTR z, e, peg, corner, roty;
  1635.      7          POS_PTR pcor;
  1636.      8          int q;
  1637.      9
  1638.     10          z = gentr_trsl("Z",  0.,  0., 864.);
  1639.     11          e = gentr_trsl("E" , 0. , 0. , 140.);
  1640.     12          peg = gentr_trsl("PEG", 0., 0., 10.);
  1641.     13          corner = gentr_trsl("CORNER", -50., 500., 550.);
  1642.     14          corner->fn = varb;
  1643.     15          roty = gentr_rot("ROTY", 0., 0., 0., yunit, 180.);
  1644.     16
  1645.     17          pcor = makeposition(
  1646.     18          "PCOR", z, t6, e, peg, EQ, corner, roty, TL, peg);
  1647.     19
  1648.     20          setvel(300, 50);
  1649.     21          move(pcor);
  1650.     22          if (!teach(corner, pcor)) {
  1651.     23                  setvel(300, 50);
  1652.     24
  1653.     25                  setmod('j');
  1654.     26                  move(park);
  1655.     27                  return;
  1656.     28          }
  1657.     29          setmod('c');
  1658.     30          setvel(100, 100);
  1659.     31
  1660.     32          distance("dz", -50.);
  1661.     33                  move(pcor);
  1662.     34
  1663.     35          QUERY(q);
  1664.     36
  1665.     37          if (q == 'n') {
  1666.     38                  setvel(300, 100);
  1667.     39                  setmod('j');
  1668.     40                  move(park);
  1669.     41                  return;
  1670.     42          }
  1671.     43          move(pcor);
  1672.     44
  1673.     45          setvel(5, 20);
  1674. .DE
  1675. .cs R
  1676. .br
  1677. .cs R 23
  1678. .DS L
  1679.     46
  1680.     47          limit("fz", 20.);
  1681.     48          distance("dz", 10.);
  1682.     49                  move(pcor);
  1683.     50          comply("fz", 10.);
  1684.     51                  limit("fy", 15.);
  1685.     52                  distance("dy", -10.);
  1686.     53                          move(pcor);
  1687.     54                  comply("fy", -10.);
  1688.     55                          update(corner, pcor);
  1689.     56                          limit("fx", 25.);
  1690.     57                          distance("dx", 10.);
  1691.     58                                  move(pcor);
  1692.     59          lock("fz fy");
  1693.     60          setvel(50, 50);
  1694.     61          distance("dx dy dz", -10., 10., -50.);
  1695.     62                  move(pcor);
  1696.     63
  1697.     64          setvel(300, 50);
  1698.     65          setmod('j');
  1699.     66          move(park);
  1700.     67          distance("dx dy dz", -10., 10., -50.);
  1701.     68                  move(pcor);
  1702.     69          setmod('c');
  1703.     70          setvel(50, 50);
  1704.     71          distance("dx dy dz", -1., 1., -1.);
  1705.     72                  move(pcor);
  1706.     73          distance("dx dy dz", -10., 10., -50.);
  1707.     74                  move(pcor);
  1708.     75          setvel(300, 50);
  1709.     76          setmod('j');
  1710.     77          move(park);
  1711.     78  }
  1712. .DE
  1713. .cs R
  1714. .PP
  1715. Again the preliminary phase is quite similar to the previous
  1716. example.
  1717. The approximate location of the corner is taught by an operator and
  1718. a chance is also given, line 32 to 43, to cancel the task.
  1719. The reader may notice that in this example, the corner is oriented
  1720. in such a way that approaching it corresponds to positive
  1721. displacements in the X and Z directions, and a negative one in the Y
  1722. direction.
  1723. The manipulator approaches the first wall of the corner moving along the
  1724. Z direction, lines 48 and 49, and enters the first
  1725. .I comply
  1726. mode, line 50, before moving to the next wall.
  1727. The same process is repeated for the Y and Z directions.
  1728. In each case a preload force is exerted in the appropriate direction
  1729. in order to maintain contact with the walls.
  1730. The last accommodation motion, line 58, is associated to a call
  1731. to
  1732. .B update
  1733. so as to record the final position.
  1734. Two compliance degrees of freedom are accumulated and the
  1735. manipulator is brought back to position servo mode line 59.
  1736. The peg is then taken away, lines 60 to 62.
  1737. Before going back to the recorded position, the arm is
  1738. moved at high velocity to the PARK position.
  1739.