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

  1. .ND
  2. .EQ
  3. delim $$
  4. .EN
  5. .nr H1 7
  6. .NH 1
  7. Structuring Programs
  8. .PP
  9. We shall attempt in this section to show how higher level primitives
  10. can be written in term of RCCL functions.
  11. We shall make use of the macro processing facilities to
  12. define in a few lines some manipulator language statements
  13. often encountered.
  14. A primitive
  15. .B insert
  16. based on a bare bone version of the insertion task explained earlier
  17. is described.
  18. This
  19. .B insert
  20. primitive, newly defined is used in a repetitive task.
  21. Each loop the manipulator moves to a `get' position where
  22. a feeder conveys pegs to be inserted on an assembly.
  23. The holes locations are stored on file and may have been taught in a
  24. previous operation or obtained from a CAD/CAM system.
  25. The loop synchronizes with the feeder's actions via an external
  26. variable :
  27. .br
  28. .cs R 23
  29. .DS L
  30.      1  #include "rccl.h"
  31.      2  #include "umac.h"
  32.      3  #include "hand.h"
  33.      4
  34.      5  #define AWAYZ(p, l)      {distance("dz", - (l)); move(p);}
  35.      6  #define OVERSHOOTZ(p, l) {distance("dz",   (l)); move(p);}
  36.      7  #define FAST             setvel(300, 300.);
  37.      8  #define SLOW             setvel(50, 50.);
  38.      9  #define CAUTIOUS         setvel(7, 7);
  39.     10
  40.     11  /*
  41.     12   * do one insertion
  42.     13   */
  43.     14
  44.     15  insert(z, grip, peg, hole, depth, ang)
  45.     16  TRSF_PTR z, grip, peg, hole;
  46.     17  real depth, ang;
  47.     18  {
  48.     19          TRSF_PTR bottom, angle, roty;
  49.     20          POS_PTR align, in, touch;
  50.     21
  51.     22          bottom = gentr_trsl("BOTTOM", 0., 0., -depth);
  52.     23          angle = gentr_rot("ANGLE", 0., 0., 0., yunit, ang);
  53.     24          roty = gentr_rot("ROTY", 0., 0., 0., yunit, 180.);
  54.     25
  55.     26          align = makeposition(
  56.     27          "ALIGN", z, t6, grip, peg, EQ, hole, angle, roty, TL, peg);
  57.     28
  58.     29          touch = makeposition(
  59.     30          "TOUCH", z, t6, grip, peg, EQ, hole, angle, roty, TL, peg);
  60.     31
  61.     32          in = makeposition(
  62.     33          "IN", z, t6, grip, peg, EQ, hole, bottom, roty, TL, peg);
  63.     34
  64. .DE
  65. .cs R
  66. .br
  67. .cs R 23
  68. .DS L
  69.     35          setmod('c');
  70.     36          FAST
  71.     37          AWAYZ(touch, 10.)
  72.     38          CAUTIOUS
  73.     39          AWAYZ(touch, 4.)
  74.     40          limit("fz", 25.);
  75.     41          OVERSHOOTZ(touch, 5.)
  76.     42          comply("fz", 15.);
  77.     43                  move(align);
  78.     44          lock("fz");
  79.     45          comply("fx fy", 0., 0.);
  80.     46                  update(hole, in);
  81.     47                  limit("fz", 20.);
  82.     48                  OVERSHOOTZ(in, 10.);
  83.     49          lock("fx fy");
  84.     50
  85.     51          SLOW
  86.     52          AWAYZ(align, 50.)
  87.     53          waitfor(in->end)
  88.     54          OPEN
  89.     55          move(there);
  90.     56          waitfor(completed);
  91.     57          freepos(align);
  92.     58          freepos(in);
  93.     59          freepos(touch);
  94.     60          freetrans(bottom);
  95.     61          freetrans(angle);
  96.     62          freetrans(roty);
  97.     63          return;
  98.     64  }
  99.     65
  100. .DE
  101. .cs R
  102. .br
  103. .cs R 23
  104. .DS L
  105.     66  /*
  106.     67   * monitors feeder
  107.     68   */
  108.     69
  109.     70  #define PARTS   1
  110.     71  #define EMPTY   2
  111.     72
  112.     73  monfeeder()
  113.     74  {
  114.     75          if (feedersensor == PARTS) {
  115.     76                  nextmove = YES;
  116.     77                  CLOSE
  117.     78          }
  118.     79          if (feedersensor == EMPTY) {
  119.     80                  parts = 0;
  120.     81          }
  121.     82  }
  122.     83
  123.     84  /*
  124.     85   * Do insertions
  125.     86   */
  126.     87
  127.     88  int parts = YES;
  128.     89
  129.     90  pumatask()
  130.     91  {
  131.     92          TRSF_PTR z, e, assy, h, feeder, grasp, pegs;
  132.     93          POS_PTR get;
  133.     94
  134.     95          z = gentr();                            /* base frame */
  135.     96          e = gentr();                            /* end effector */
  136.     97          assy = gentr();                         /* assembly */
  137.     98          grasp = gentr();                        /* gasp pos */
  138.     99          feeder = gentr();                       /* feeder */
  139.    100          pegs = gentr();                         /* peg rel. e */
  140.    101          h = newtrans("H", hold);                /* h rel. to assy */
  141.    102
  142.    103          get = makeposition("GET", z, t6, e, EQ, feeder, grasp, TL, e);
  143.    104
  144.    105          while(parts) {
  145.    106                  move(get);
  146.    107                  evalfn(monfeeder);
  147.    108                  setime(200, 10000);
  148.    109                  move(get);
  149.    110                  gettr(h, file);
  150.    111                  insert(z, e, pegs, h, 20., 15.);
  151.    112          }
  152.    113  }
  153. .DE
  154. .cs R
  155. .bp
  156. .PP
  157. Conveyors are expensive, and rugged objects could be thrown from place
  158. to place.
  159. We shall see here how a `throw' primitive (seldom found in regular
  160. robot programming languages) can be easily written.
  161. In order to obtain a maximum acceleration, we shall program a sequence of
  162. motions that only uses the transition part.
  163. This example is only given as an illustration because the
  164. dynamic qualities of the Puma manipulator proved to be not quite sufficient.
  165. .br
  166. .cs R 23
  167. .DS L
  168.      1  #include "rccl.h"
  169.      2  #include "hand.h"
  170.      3  #include "umac.h"
  171.      4
  172.      5  real when;              /* to open the gripper */
  173.      6
  174.      7  #define MAXACC  .015    /* mm/ms2 */
  175.      8
  176.      9  throw(v0)
  177.     10  VECT_PTR v0;
  178.     11  {
  179.     12          int openat();
  180.     13
  181.     14          real Tx = (12. * v0->x) / MAXACC;       /* compute          */
  182.     15          real Ty = (12. * v0->y) / MAXACC;       /* the acceleration */
  183.     16          real Tz = (12. * v0->z) / MAXACC;       /* times            */
  184.     17          int  T = ((FABS(Tx) > (Ty))             /* and pick up      */
  185.     18                          ? ((FABS(Tx) > FABS(Tz))
  186.     19                                  ? Tx : Tz)      /* the longest one  */
  187.     20                          : ((FABS(Ty) > FABS(Tz))
  188.     21                                  ? Ty : Tz));
  189.     22
  190.     23          real dx, dy, dz;
  191.     24
  192.     25          stop(0);
  193.     26          setmod('c');
  194.     27          dx = Tx * v0->x / 2.;
  195.     28          dy = Ty * v0->y / 2.;
  196.     29          dz = Tz * v0->z / 2.;
  197.     30
  198.     31          distance("dx dy dz", -dx, -dy, -dz);
  199.     32          setime(T / 2, T);
  200.     33          move(there);            /* back up      */
  201.     34
  202.     35          when = .90;             /* open the gripper just */
  203.     36          evalfn(openat);         /* before the end        */
  204.     37          distance("dx dy dz", 2. * dx,  2. * dy,  2. * dz);
  205.     38          setime(T / 2, T);
  206.     39          move(there);            /* move as fast as possible */
  207.     40
  208.     41          setime(T / 2, T);       /* come back            */
  209.     42          move(there);
  210.     43          stop(0);
  211.     44          return;
  212.     45  }
  213.     46
  214.     47
  215.     48  openat() /* opens the gripper at a given moment */
  216.     49  {
  217.     50          if (goalpos->scal >= when) {
  218.     51                  OPEN
  219.     52          }
  220.     53  }
  221. .DE
  222. .cs R
  223. .br
  224. .cs R 23
  225. .DS L
  226.     54
  227.     55  pumatask()
  228.     56  {
  229.     57          TRSF_PTR b0, grip;
  230.     58          POS_PTR p0;
  231.     59          VECT vel;
  232.     60          int q;
  233.     61
  234.     62          grip = gentr_trsl("GRIP", 0., 0., 170.);
  235.     63          b0 = gentr_rot("B0", 400., 150., 700., yunit, 45.);
  236.     64
  237.     65          p0 = makeposition("P0", t6, grip, EQ, b0, TL ,grip);
  238.     66
  239.     67          QUERY(q)
  240.     68          CLOSE
  241.     69          setconf("d");   /* elbow down, like the Great Di Maggio */
  242.     70          setime(100, 3000);
  243.     71          move(p0);               /* move above the shoulder */
  244.     72          vel.x = .0;
  245.     73          vel.y = .0;
  246.     74          vel.z = .6;             /* m/s at 45 degrees, see B0 */
  247.     75
  248.     76          throw(&vel);
  249.     77
  250.     78          setmod('j');            /* back to park */
  251.     79          setconf("u");           /* elbow up     */
  252.     80          setime(100, 3000);
  253.     81          move(park);
  254.     82  }
  255. .DE
  256. .cs R
  257. The acceleration times , lines 14 to 21, and the magnitudes, lines 27 to 29,
  258. are derived from the coefficients of
  259. the quartic polynomial
  260. functions used to generate the transitions [2].
  261. The segment times are exactly twice the accelerations times.
  262. .bp
  263. .NH
  264. Limitations
  265. .NH 2
  266. Force Control
  267. .PP
  268. In the case of the Puma manipulator,
  269. the implementation of force control suffers a number a limitations
  270. due to the simplicity of the implemented method.
  271. Force measurements are obtained by monitoring the motor currents.
  272. Coulomb friction terms, at the joint level,
  273. have been experimently measured [8].
  274. When the velocity of a joint is small or null, these terms are
  275. irrelevant and cannot be used to improve the accuracy of the control.
  276. When the arm if to stop on force, this is of little importance since
  277. the joints likely to provide the guarded motion are moving.
  278. Nevertheless, this fact has to be kept in mind.
  279. Gravity loadings have also been experimently measured.
  280. Experiments have shown that although the mass of an object carried by
  281. the manipulator could be measured, the accuracy is not sufficient
  282. and is likely to cause offset errors for the gravity loadings.
  283. The function
  284. .B massis
  285. has been implemented to get around this.
  286. .PP
  287. Force specifications possess an estimated accuracy
  288. of approximately 10 Newton in most of the work space.
  289. This is pretty close to the load capabilities of the manipulator,
  290. therefore extreme prudence is recommanded.
  291. Despite this lack of accuracy, the tasks using force control
  292. explained in this document all run with a good reliability.
  293. .PP
  294. When the manipulator transitions from
  295. .I comply
  296. servo mode to
  297. .I position
  298. servo mode, a glitch often occurs and is as noticeable as the velocity is high
  299. and the load important.
  300. It is usually harmless, and correspond to the position
  301. servo correcting the first setpoint.
  302. .PP
  303. Compliance in a given direction is obtained by selecting the
  304. joints most suitable to provide the desired effects [2].
  305. The joint selection method is simplified.
  306. It does not take into account the translation part the
  307. .I tool
  308. frame.
  309. This means that in
  310. .I comply
  311. servo mode, force specifications will always
  312. match the inner joints (1, 2, 3) and torques specifications the wrist
  313. joints (4, 5, 6).
  314. Although the method is reliable and simple, it suffers
  315. the drawback that no remote center of compliance can be specified.
  316. Time constraints have prevented further work on this points, and
  317. any contributions are welcome.
  318. .NH 2
  319. Machine Errors.
  320. .PP
  321. When the robot task is running in real time, the process
  322. is locked into core memory and the interrupt function
  323. of the system as well as the user's background functions
  324. are run at very high priority in kernel mode.
  325. Any system call (machine trap), will crash the system (beware of the prints).
  326. The same problem occurs for any machine error like a bad memory reference
  327. of a floating point exception in any part of the process.
  328. Some debugging tools are provided as explained later.
  329. .NH 2
  330. Process Size
  331. .PP
  332. When the real time process is run, it is locked into core memory
  333. and the virtual memory system desactivated.
  334. Therefore, the process cannot grow it's allocated region.
  335. Dynamic allocation is performed within a preallocated memory area.
  336. The system calls like `malloc' are replaced by alternative
  337. functions [6].
  338. A set a macros :
  339. .br
  340. .cs R 23
  341. .DS L
  342. #define malloc  malloc_l
  343. #define free    free_l
  344. #define realloc realloc_l
  345. #define calloc  calloc_l
  346. #define cfree   cfree_l
  347.  
  348. .DE
  349. .cs R
  350. allows the user to safely write :
  351. .br
  352. .cs R 23
  353. .DS L
  354.         p = malloc(20);
  355. .DE
  356. .cs R
  357. .PP
  358. This causes a more annoying problem when it comes to opening files.
  359. Files can be opened only when the real time channel is closed.
  360. However, the user can always code :
  361. .br
  362. .cs R 23
  363. .DS L
  364.         ...
  365.         move(p);
  366.         stop(200);
  367.         waitfor(completed);
  368.         release("opening files");
  369.         fd1 = creat(...
  370.         fd2 = open(...
  371.  
  372.         startup();
  373.         move(...);
  374. .DE
  375. .cs R
  376. The process is temporally put back in normal mode by the function
  377. .B release
  378. [6], and file `opens' can
  379. take place.
  380. The function
  381. .B startup
  382. will resume real time execution by the depressing the ARM POWER
  383. button when requested by the system.
  384. Failing to follow the procedure will also cause a system crash.
  385. .NH 2
  386. Sample
  387. .PP
  388. The sample period is normally 28 ms.
  389. It can be set to 14 via the function
  390. .B sample
  391. and when not needed, the sample period can be reset to 28 ms.
  392. Changing the sample period can cause a slight glitch.
  393. If the velocity if the manipulator is small, the glitch is negligible.
  394. For example the for loop of the example section 7.3
  395. can be coded :
  396. .br
  397. .cs R 23
  398. .DS L
  399.     32          for (; ; ) {
  400.     33                  setvel(400, 300);
  401.     34                  move(get);
  402.     35                  move(p1);
  403.                         stop(0);
  404.     36                  setvel(100, 100);
  405.     37                  sample(15);
  406.     38                  move(p2);
  407.                         stop(0);
  408.     39                  sample(30);
  409.     40                  printf("more ?"); QUERY(q); if (q == 'n') break;
  410.     41          }
  411. .DE
  412. .cs R
  413. .PP
  414. If the user's background functions take to much time to execute, the
  415. behavior of the real time interface no always easy to predict.
  416. In the best cases, it causes a crash of the superviser program running
  417. in the LSI-11.
  418. The arm power is immediately turned off, and nothing annoying happens.
  419. The superviser is restarted and everything comes back to
  420. normal.
  421. It seems that when the user's functions processing time is slightly too long,
  422. the VAX still accepts interrupts, but stacks them and this quickly
  423. causes a system crash.
  424. Finally, if the interrupt code is very long (an infinite loop, for example),
  425. the system is totally blocked and a manual boot is necessary.
  426. .NH 2
  427. Large Rotations.
  428. .PP
  429. For a reason that has not been yet determined, some motion transitions
  430. involving large rotations do not behave quite correctly.
  431. .NH
  432. The Planner and Play Program
  433. .PP
  434. In order to write and debug the first draft of manipulator
  435. programs, a special library is provided.
  436. This library has exactly the same entry points as the regular
  437. library, but replaces the interrupt code with a loop.
  438. Exactly the same programs can by run and tested.
  439. The synchronization features are simulated so that everything happens
  440. in the same order as in the real time version.
  441. The user is advised to run the programs in this mode
  442. before actual execution.
  443. The resulting sequence of points can be dumped onto file
  444. for execution by the
  445. .I play
  446. program [6].
  447. Trajectories can be also stored and displayed on the terminal
  448. by a special program
  449. called
  450. .I dsp.
  451. .PP
  452. When programs with guarded motions are run in this fashion,
  453. the conditions will never be met, unless
  454. special simulation monitoring functions are written.
  455. When programs include comply statements, the comply mode is
  456. simulated as follow :
  457. the compliant joints are selected according to the geometry of the task
  458. and are artificially frozen as if the resulting forces would keep
  459. them immobile.
  460. The accommodation motions compensation feature being still activated,
  461. it may produce
  462. funny but meaningful trajectories.
  463. Tracking with external information can produce various results
  464. according to the situation at hand.
  465. Nevertheless it is very useful to test ahead manipulator programs.
  466. All  branches must be tested because manipulator control is
  467. essentially programming with side effects.
  468. It is always useful to `play' the resulting trajectories in free
  469. space to get an idea of what is going to happen.
  470. .bp
  471. .NH
  472. Program Options
  473. .PP
  474. Programs can be run with a number of options :
  475.  
  476. .IP v
  477. This option allows the user to specify the printing of information.
  478. A file called `@@.out' is created in the current directory.
  479. It contains informations about what the system understood of the
  480. calls to
  481. .B makeposition.
  482. A record will be printed for each move request.
  483. For the planning version only, a record will be printed by
  484. the trajectory generator at the time the request is executed, for example
  485. the beginning of the file `@@.out' for the camera guided task
  486. Section 7.1. is :
  487. .br
  488. .cs R 23
  489. .DS L
  490. makeposition, pos       "LOOK"  Z T6 E  = EXPECT
  491. optim, initial equation :       T6 =  -Z EXPECT -E
  492. optim, final equation   :       T6 =  _TEMP1 -E
  493.         "COORD":  "TOOL": -E  "POS": _TEMP1
  494.  
  495. makeposition, pos       "GET"   T6 E  = COORD CAM O
  496. optim, initial equation :       T6 =  COORD(h) CAM O(h) -E
  497. optim, final equation   :       T6 =  COORD(h) CAM O(h) -E
  498.         "COORD": COORD(h) CAM  "TOOL": -E  "POS": O(h)
  499.  
  500. makeposition, pos       "PUT"   Z T6 E  = DROP
  501. optim, initial equation :       T6 =  -Z DROP -E
  502. optim, final equation   :       T6 =  _TEMP2 -E
  503.         "COORD":  "TOOL": -E  "POS": _TEMP2
  504.  
  505. .DE
  506. .cs R
  507. .br
  508. .cs R 23
  509. .DS L
  510. request LOOK mode j acct 56  sgt 0  velt 200 velr 100
  511. conf    upd :  smpl 0 mass 0.000000
  512.  
  513. PARK -1 28 j 84 84 280 28
  514.         force 00 0 0 0 0 0 0
  515.         cply  00 0 0 0 0 0 0
  516.         dst   00 0 0 0 0 0 0
  517.         exd   00 0 0 0 0 0 0
  518. LOOK -1 336 j 56 56 2660 28
  519.         force 00 0 0 0 0 0 0
  520.         cply  00 0 0 0 0 0 0
  521.         dst   00 0 0 0 0 0 0
  522.         exd   00 0 0 0 0 0 0
  523. .DE
  524. .cs R
  525. .br
  526. .cs R 23
  527. .DS L
  528. request GET mode j acct 56  sgt 0  velt 200 velr 100
  529. conf    upd :  smpl 0 mass 0.000000
  530. dist dz : -30
  531.  
  532. request GET mode j acct 56  sgt 0  velt 200 velr 100
  533. conf    upd :  smpl 0 mass 0.000000
  534.  
  535. request STOP mode j acct 0  sgt 28  velt 200 velr 100
  536. conf    upd :  smpl 0 mass 0.000000
  537.  
  538. request GET mode j acct 56  sgt 0  velt 200 velr 100
  539. conf    upd :  smpl 0 mass 0.000000
  540. dist dz : -30
  541.  
  542. GET -1 3024 j 56 56 1568 28
  543.         force 00 0 0 0 0 0 0
  544.         cply  00 0 0 0 0 0 0
  545.         dst   00 0 0 0 0 0 0
  546.         exd   04 0 0 -30 0 0 0
  547. GET -1 4592 j 56 56 280 28
  548.         force 00 0 0 0 0 0 0
  549.         cply  00 0 0 0 0 0 0
  550.         dst   00 0 0 0 0 0 0
  551.         exd   00 0 0 0 0 0 0
  552. GET -1 4872 j 56 56 140 28
  553.         force 00 0 0 0 0 0 0
  554.         cply  00 0 0 0 0 0 0
  555.         dst   00 0 0 0 0 0 0
  556.         exd   00 0 0 0 0 0 0
  557. .DE
  558. .cs R
  559. .br
  560. .cs R 23
  561. .DS L
  562. request PUT mode j acct 56  sgt 0  velt 200 velr 100
  563. conf    upd :  smpl 0 mass 0.000000
  564.  
  565. GET -1 5012 j 56 56 280 28
  566.         force 00 0 0 0 0 0 0
  567.         cply  00 0 0 0 0 0 0
  568.         dst   00 0 0 0 0 0 0
  569.         exd   04 0 0 -30 0 0 0
  570. PUT -1 5292 j 56 56 2492 28
  571.         force 00 0 0 0 0 0 0
  572.         cply  00 0 0 0 0 0 0
  573.         dst   00 0 0 0 0 0 0
  574.         exd   00 0 0 0 0 0 0
  575. PUT -1 7784 j 56 56 112 28
  576.         force 00 0 0 0 0 0 0
  577.         cply  00 0 0 0 0 0 0
  578.         dst   00 0 0 0 0 0 0
  579.         exd   00 0 0 0 0 0 0
  580. request LOOK mode j acct 56  sgt 0  velt 200 velr 100
  581. conf    upd :  smpl 0 mass 0.000000
  582.  
  583. Etc ...
  584.  
  585. .DE
  586. .cs R
  587. The equations are printed, then their canonized form before and
  588. after optimization.
  589. Transforms are marked according to their type : varb (v), hold (h),
  590. functional (s).
  591. The optimization premultiplications generate the `_TEMPx' names.
  592. For each request all the parameters are printed, for example :
  593. .br
  594. .cs R 23
  595. .DS L
  596. request LOOK mode j acct 56  sgt 0  velt 200 velr 100
  597. conf    upd :  smpl 0 mass 0.000000
  598. .DE
  599. .cs R
  600. means : position `LOOK', mode `joint', acceleration time 56 ms,
  601. segment time is 0 that is : will be computed at execution time,
  602. current velocities are 200 mm/s and 100 deg/s, no configuration change
  603. required, no transform to update, no sample time change, current mass of
  604. object is 0. kg.
  605. .IP
  606. The trajectory generator prints in a compact format the specification
  607. at the beginning of each motion (planning version only) :
  608. .br
  609. .cs R 23
  610. .DS L
  611. GET -1 5012 j 56 56 280 28
  612.         force 00 0 0 0 0 0 0
  613.         cply  00 0 0 0 0 0 0
  614.         dst   00 0 0 0 0 0 0
  615.         exd   04 0 0 -30 0 0 0
  616. .DE
  617. .cs R
  618. means : previous motion terminated `OK' (-1), time is 5012 ms,
  619. mode is `joint', accelerations times first transition is 56, second 56,
  620. segment time is 280, time increment is 28.
  621. No force limit, no comply, no differential motion stop, distance is
  622. -30 mm in Z direction.
  623. For the records `force', `cpy', `dst', and `exd', the first number is
  624. an octal code (00 for no specification, translation or forces :
  625. 01 for X, 02 for Y, 04 for Z, rotations or torques : 10 for X, 20 for Y,
  626. 40 for Z, and the combinations : 01, 03, 05, 06, etc ...);
  627. .IP
  628. If the the option `-vv' as very verbose is given, the values
  629. of the transforms created by the `gentr...' style function is also
  630. printed.
  631. .IP
  632. This option corresponds to the global flag
  633. .B prints_out.
  634. This flag can be turned on or off the text of the programs
  635. themselves :
  636. .br
  637. .cs R 23
  638. .DS L
  639.         ...
  640.         prints_out = YES;
  641.         p0 = makeposition(...);
  642.         p1 = makeposition(...);
  643.  
  644.         move(p0);
  645.         move(p1);
  646.         prints_out = NO;
  647. .DE
  648. .cs R
  649. The information is printed to the
  650. .B fpi
  651. file pointer :
  652. .br
  653. .cs R 23
  654. .DS L
  655.         FILE *fpi;
  656. .DE
  657. .cs R
  658. This file pointer is initialized to the `stderr' file pointer.
  659. When the flag
  660. .B prints_out
  661. is set to a non zero value, the
  662. .B makeposition
  663. and
  664. .B move
  665. messages go to the terminal.
  666. When the option `-v' is specified, the file `@@.out' is created and
  667. .B fpi
  668. points to it, and the messages are stored on the file.
  669. One can use this feature for any purposes, for example :
  670. .br
  671. .cs R 23
  672. .DS L
  673. pumatask()
  674. {
  675.         TRSF_PTR ...
  676.         POS_PTR ...
  677.         ...
  678.  
  679.         prints_out = NO;
  680.         p = makeposition(...);
  681.         ...
  682.  
  683.         move(p);
  684.         ...
  685.         fprintf(fpi, "bla bla");
  686.         ...
  687. }
  688. .DE
  689. .cs R
  690. If the task is run without option `-v', "bla bla" goes on `stderr' file,
  691. if the task is run with option `-v', "bla bla" goes into `@@.out'.
  692.  
  693. .IP g
  694. This is the `graphic' option (planing version only).
  695. The setpoints are stored in the
  696. files `../g/f1.out', `../g/f2.out', one for each joint.
  697. When displayed with the program
  698. .I dsp
  699. a character `J' stands for joint mode straight part, `T' for joint mode
  700. transition, `E' for first point of joint mode transition, `C' for
  701. a Cartesian mode straight part, `H' for Cartesian transition, and `V'
  702. for first point of Cartesian transition.
  703. In order to use this option, the user is required to have a `graphic'
  704. directory `../g' at the same level in the file tree
  705. hierarchy as the current directory.
  706. This will avoid having the current directory constantly clustered with
  707. junk files.
  708.  
  709. .IP d
  710. This is the `data' option (planning version only),
  711. when specified, the system creates
  712. the file `@.out' in the current directory that will contain one line
  713. per setpoint according to the following format :
  714. .br
  715. .cs R 23
  716. .DS L
  717.      POS M  time tseg j1  j2  j3  j4  j5  j6 sel
  718. .DE
  719. .cs R
  720. Where `POS' is the name of the goal position, `M' is the mode
  721. (J, T, E, C ,V ,H)
  722. as described above, `j1'...`j6' are the joint angles in range coordinate [6],
  723. and `sel' an octal value showing which joint are complying in comply mode
  724. (0 no joint, 01 for joint 1 , 02 for joint 2, 04 for joint 3, 10 for joint 4,
  725. 20 for joint 5, 40 for joint 6, 3 for joint 1 and 2, etc. ).
  726.  
  727. .IP a
  728. This option when set, causes the joint angles to be output in solution
  729. coordinates [6].
  730. It serves for option `d' and `g'.
  731.  
  732. .IP k
  733. This option when set, causes the values of $T6$ to be printed in lieu
  734. of the joint angles.
  735. For the option `g' twelve files (f1.out ... f12.out) are created,
  736. the values of the vectors `p', `n', `o', and `a';
  737. For the option `d' the format becomes :
  738. .br
  739. .cs R 23
  740. .DS L
  741.      POS M  time tseg px  py  pz  nx  ny  nz ox oy oz ax ay az
  742. .DE
  743. .cs R
  744. It serves for option `d' and `g'.
  745.  
  746. .IP e
  747. This option causes the file `@@@.out' to be created in the
  748. current directory (planing version only).
  749. The file contains the sequence of encoder values suitable to be
  750. used by the
  751. .I play
  752. program [6].
  753.  
  754. .IP "Dname "
  755. This option specifies the file `name' as a data base of transforms.
  756. Can be used in association with the teach mode (see below).
  757. .IP
  758. This option corresponds to the global file descriptor
  759. .B fddb
  760. initialized to `-1'.
  761. When the option `-Dname' is specified,
  762. .B fddb
  763. describes the file `name'.
  764. If the file `name' does not exit the user is prompt as :
  765. .br
  766. .cs R 23
  767. .DS L
  768. name does'nt exit, create ? (y/n)
  769. .DE
  770. .cs R
  771. Answer as appropriate.
  772.  
  773. .IP b
  774. This option turns off the force control features (brute option).
  775. In the case of the planning version, no simulated joint accommodation
  776. will occur.
  777. In the case of the real time version, it allows us to test the manipulator
  778. programs free of obstacles.
  779. .IP
  780. This option corresponds to the global flag
  781. .B force_ctl
  782. which is turn off by the `-b' option.
  783. The flag can be turned on or off in the text of the programs.
  784.