home *** CD-ROM | disk | FTP | other *** search
/ Programmer 7500 / MAX_PROGRAMMERS.iso / INFO / C / ROBOT01.ZIP / RCCL011 < prev    next >
Encoding:
Text File  |  1987-03-02  |  31.1 KB  |  1,127 lines

  1. .ND
  2. .FS
  3. This work was partially supported by a Grant from the CNRS
  4. project ARA (Automatique et Robotique Avanc\o"e\'"e), France, and
  5. by the Ransburg Chair of Robotics.
  6. This material is also based on work supported by the National
  7. Science Foundation under the Grant No. MEA-8119884.
  8. Any opinions, findings, conclusions, or recommendations
  9. expressed in this publication are those of the authors
  10. and do not necessarily reflect the views of the National
  11. Science Foundation.
  12. Facilities to perform this research are provided by the Purdue University
  13. CIDMAC
  14. project.
  15. .FE
  16. .ce 1
  17. Robot Real Time Control User's Manual
  18. .sp 7
  19. .ce 1
  20. Vincent Hayward
  21. .sp 5
  22. .ce 3
  23. School of Electrical Engineering
  24. Purdue University
  25. West Lafayette, Indiana, 47907
  26. .sp 5
  27. .ce 1
  28. TR-EE 83-42
  29. .sp 5
  30. .ce 1
  31. October 1983
  32. .bp
  33. .EQ
  34. delim $$
  35. .EN
  36. .NH
  37. Overview
  38. .PP
  39. This manual describes how to implement real time programs
  40. to control the robots situated in room B20 at Potter Building.
  41. The Stanford and the Puma 600 arms can be equally used.
  42. The system consist of :
  43. .IP *
  44. an executable module, called the superviser, which is to be
  45. loaded down to the robot controller's lsi11 processor;
  46. .IP *
  47. a UNIX library containing several entry points:
  48. .RS
  49. .IP -
  50. a function
  51. .B control()
  52. which permits to open the robot channel
  53. and makes the vax sensitive to controller's interrupts;
  54. .IP -
  55. a function
  56. .B release()
  57. which shuts off the arm and closes the channel;
  58. .IP -
  59. a function
  60. .B adcopen()
  61. for specifying analog to digital conversions.
  62. .IP -
  63. a "C" structure
  64. .B how
  65. describing the robot state
  66. updated at sample time intervals;
  67. .IP -
  68. a "C" structure
  69. .B chg
  70. describing the different commands that
  71. are likely to be sent to the arm controller;
  72. .IP -
  73. a flag
  74. .B terminate
  75. to indicate when the real-time interaction
  76. should terminate;
  77. .IP -
  78. a pointer to a string
  79. .B mess
  80. that will be printed at the termination
  81. of the real-time interaction;
  82. .IP -
  83. a function
  84. .B stepmode()
  85. that permits to manually move each joint
  86. from the terminal;
  87. .IP -
  88. mapping functions:
  89. .B
  90. enctoang(), rngtoang(),
  91. .R
  92. etc... (see appendix).
  93. .RE
  94. .IP *
  95. an include file
  96. .B rtc.h
  97. describing the structures
  98. .B how
  99. and
  100. .B chg
  101. ;
  102. .NH
  103. Real Time Considerations
  104. .PP
  105. Real time programming offers several peculiar aspects which
  106. have to be mentioned here.
  107. A real time program consists of two parts.
  108. The main function, executed in time sharing, allows
  109. the program to communicate with the rest of the system.
  110. It can contain system calls, as disk or terminal
  111. input-output, etc ...
  112. The interrupt routines, activated upon controller interrupt,
  113. are executed in kernel mode for efficiency.
  114. Their execution time must be limited and therefore, they
  115. .B cannot
  116. perform
  117. .B any
  118. type of system call (read(2), write, fork(2),
  119. signal(2), exec(2), brk(2) and so on).
  120. .PP
  121. Any machine error as floating point exception or bad memory reference
  122. occurring during the execution of
  123. the interrupt functions will produce a system crash.
  124. The program cannot grow it's allocated region therefore any
  125. calls like fork(2), open(2), malloc(2) must not be invoked when
  126. the channel is open.
  127. However, this type of calls can be performed before opening
  128. the channel ,which is a minor burden.
  129. If you need to use dynamic memory allocation, the package provides
  130. alternative entry points (see Appendix) to perform similar functions
  131. (alloc/free) but within a pre-allocated pool of memory.
  132. Since the capacity is limited, caution must be taken
  133. to insure that the allocations are successful.
  134. .PP
  135. The interrupt functions are called from the robot interface
  136. package without any argument and are executed at very high priority.
  137. Therefore, they can only communicated with the rest of the program
  138. via global variables, which makes the programming more difficult.
  139. A systematic use of structured data types and of the 'lint' program
  140. is strongly recommanded.
  141. .PP
  142. The package makes use of SIGINT (signal(2)) to terminate the
  143. real time interaction and to shut off the arm. The real time
  144. driver makes use of SIGHUP (signal(2)) to signal a hardware
  145. error to the package. Therefore, SIGINT and SIGHUP must
  146. .B not
  147. be caught by the user.
  148. Interaction can be terminated either by setting the global
  149. variable
  150. .B terminate
  151. to 'YES' from the main program or from the interrupt
  152. functions.
  153. The same effect is achieved by typing a 'break' or often a 'rub' on the
  154. terminal (see stty(2)).
  155. The main function must remain active throughout the execution
  156. of the real time program.
  157. You will have to code something like :
  158. .DS L
  159.  
  160.         while(!terminate) {
  161.                 /* do time sharing */
  162.         }
  163.         release("finished");
  164. .DE
  165. .PP
  166. The termination will be properly produced either by a 'break'
  167. at the terminal or by setting
  168. .B terminate
  169. to YES anywhere
  170. in the program.
  171. .NH
  172. The 'How' Structure
  173. .PP
  174. The
  175. .B how
  176. structure describes the current state of the arm and
  177. is updated at interrupt time.
  178. .DS L
  179. struct how {
  180.         unsigned short
  181.                 exio,                   /* state of the extern io register */
  182.                 pos[NJOINTS];           /* current positions */
  183.         short
  184.                 adcr[ADC];              /* adc readings */
  185. };
  186. .DE
  187. .PP
  188. The content of the external i/o register reflects the state
  189. of the switches on the front panel.
  190. Normal usage of the interface does not require to pay any attention to
  191. the register's content.
  192. Positions are specified in
  193. .B encoder
  194. values.
  195. See appendix for mapping the encoders values
  196. onto the trigonometric circle, or on a physical linear scale.
  197. The
  198. .B how
  199. structure can be read either synchronously
  200. by the interrupt code or asynchronously by the main program.
  201. The first 'NJOINTS' elements of the 'adcr' array are by default
  202. the adc readings reflecting the motor currents of the manipulator's joints.
  203. The 'adcr' values are in adc readings and have to be scaled by mean
  204. of some calibration program.
  205. .NH
  206. The 'Chg' Structure
  207. .PP
  208. The
  209. .B chg
  210. structure describes the commands that the user wants
  211. to be executed by the robot controller.
  212. It is made of sub-structures which correspond to the four following
  213. cases:
  214. .IP -
  215. A command is to be sent individually to a particular joint processor.
  216. Their name is of the form 'i_name'. For each concerned command,
  217. the structure 'chg' contains an array of these structures, one per
  218. joint.
  219. Each of the 'i_name' structure contains one value field.
  220.  
  221. .IP -
  222. The same command is to be send to all the joint processors.
  223. Their name is of the form 'a_name'.
  224. For each concerned command, the structure 'chg' contains an instance
  225. of a 'a_name' structure, but the value field is an array.
  226. Using one 'a_command' is equivalent to use 'NJOINTS' 'i_commands', but
  227. is more concise, and more efficient as far as the transmission time
  228. and the command execution time are concerned.
  229.  
  230. .IP -
  231. The same command is to be sent to all the joint processors, but
  232. the same value is to be set in each joint processor.
  233. They are named 'g_name' commands.
  234. A 'g_command' contains one value field.
  235.  
  236. .IP -
  237. The last case is a command which does not need any transmitted value.
  238. .PP
  239. The following shows the structure
  240. .B chg
  241. and the various combinations
  242. of commands:
  243. .DS L
  244. struct i {
  245.         char set;               /* flag to be set if i_command requested */
  246.         unsigned short vali;    /* corresponding value */
  247. };
  248.  
  249. struct a {
  250.         char set ;              /* flag to be set if a_command requested */
  251.         unsigned short vala[NJOINTS];   /* corresponding values */
  252. };
  253.  
  254. struct g {
  255.         char set;               /* flag to be set if g_command requested */
  256.         unsigned short valg;    /* corresponding value */
  257. };
  258.  
  259.  
  260. struct chg {
  261.         struct i i_motion[NJOINTS];      /* case POS - CUR - STOP */
  262.         struct a a_motion;
  263.  
  264.         struct g g_hand;                /* command hand */
  265.         struct g g_rate;                /* rate in 2 ** value * 7 ms */
  266.  
  267.         char end;                       /* termination */
  268.         char stop;                      /* stop on the spot */
  269. };
  270. .DE
  271. .PP
  272. The actual chg structure in the rtc.h file may exhibit other instances
  273. of 'a', 'i', or 'g' structures.
  274. However, the following briefly describes the commands you are concerned with.
  275. .IP "motion : " 11
  276. Specify a position servo if the flag is raised with 'POS' value.
  277. Specify a motor current if the flag is raised with 'CUR' value.
  278. .FS
  279. The values of POS, CUR, STOP, STOPCAL, NJOINTS, ADC, YES, NO,
  280. are '#defined' and must not be redefined.
  281. .FE
  282. .IP "rate : "   11
  283. Modify the sampling rate, or in other terms, the interrupt interval
  284. time, it is expressed in powers of two times 7 milli-second.
  285. .IP  "stop : "  11
  286. Let the joint processor servo on the last position value.
  287. .IP "hand : "   11
  288. Control the hand.
  289. Meaning dependent on particular experiments.
  290. .NH
  291. Sequence of operations
  292. .NH 2
  293. Opening the Channel
  294. .PP
  295. The package provides the
  296. .B control
  297. function to open the robot's
  298. device and initialize the communication. This function takes
  299. two arguments which are pointers to the functions that you
  300. want to be executed on interrupt.
  301. The purpose of these two functions is explained in the next
  302. paragraph.
  303. Before you tell the controller to start interrupting the vax,
  304. you must make sure that the device is opened and your program
  305. is waiting for interrupts.
  306. Once the channel is opened, the user must not catch the
  307. SIGINT and SIGHUP signals (see signal(2)).
  308. The minimum code will look like:
  309. .DS L
  310. #include "rtc.h"                /* include communication declarations */
  311.                                 /* global variables */
  312.  ...
  313.  
  314. main()
  315. {
  316.         int fn1(), fn2();       /* declare real time functions */
  317.  
  318.         control(fn1, fn2);      /* open channel */
  319.         while (!terminate)      /* wait for the end */
  320.                 nap(10);
  321.         release("all done");
  322. }
  323.  
  324. fn1()
  325. {
  326. }
  327.  
  328. fn2()
  329. {
  330.         extern struct how how;
  331.         extern struct chg chg;
  332.  
  333.         ...                     /* read arm state in how */
  334.         ...                     /* compute next point, put commands in chg */
  335. }
  336.  
  337. .DE
  338. .PP
  339. While the program is 'pausing' or 'napping' you will start the
  340. superviser program by depressing the 'ARM POWER' push button and
  341. the interaction will take place.
  342. A 'break' at the terminal will cause the
  343. .B release
  344. function to be automatically called and
  345. the message "** Interrupted" printed on the terminal.
  346. However, it can be a good idea to systematically terminate your
  347. programs to a call to
  348. .B release.
  349. Failing to issue this call by one mean or another will leave the
  350. device opened and therefore unable to be re-opened.
  351. So, make sure that 'exit's in your programs are preceded by
  352. a call to
  353. .B release
  354. as shown in paragraph 2.
  355. The function
  356. .B release
  357. expects a character
  358. string argument as message to be printed when the channel is
  359. explicitly closed.
  360. .PP
  361. Note that a valid organization can be:
  362. .DS L
  363. #include "rtc.h"                /* include communication declarations */
  364.  
  365.  ...                            /* global variables */
  366.  
  367. main()
  368. {
  369.         int fn1(), fn2();       /* declare real time functions */
  370.  
  371.         control(fn1, fn2);      /* open channel */
  372.         pause();                /* wait for the program to be broken */
  373. }
  374.  
  375. fn1()
  376. {
  377. }
  378.  
  379. fn2()
  380. {
  381.         extern struct how how;
  382.         extern struct chg chg;
  383.  
  384.         ...                     /* read arm state in how */
  385.         ...                     /* compute next point, put commands in chg */
  386. }
  387.  
  388. .DE
  389. .PP
  390. If analog to digital conversions are needed, the
  391. .B adcopen
  392. function allows
  393. to select the physical adc channels.
  394. The function
  395. .B adcopen
  396. must be called from the time sharing code after
  397. a call to
  398. .B control.
  399. This function transmits to the lsi a request as to send back to your
  400. program the readings of the selected adc channel.
  401. The function
  402. .B adcopen
  403. returns an integer that is the index in
  404. the array 'adcr' of the corresponding channel.
  405. The first 6 channels are used to measure the motor currents,
  406. channels 0 through 5 are
  407. therefore opened by default and cannot be reopened.
  408. Motor currents can be
  409. read in positions 0 to 5 of the array 'adcr'.
  410. The function
  411. .B adcopen
  412. returns -1 if the
  413. channel is  already opened, or the argument invalid, or
  414. .B control
  415. is not
  416. active.  Up to 10 channels can be used (6 through 15).
  417. .PP
  418. Example :
  419. A sensor is wired to channel 7, in order to use it the code may look like:
  420. .DS L
  421. #define SENSORCHANNEL   7
  422.  
  423. int sensor = -1;
  424.  
  425. main()
  426. {
  427.         blabla;
  428.         ...
  429.         control(f1, f2);
  430.         sensor = adcopen(SENSORCHANNEL);
  431.         while (!terminate) {
  432.                 nap(10);
  433.         }
  434.         release("happy");
  435. }
  436.  
  437. f1()
  438. {
  439. }
  440.  
  441. f2()
  442. {
  443.         if (sensor < 0) {       /* not ready yet */
  444.                 return;
  445.         }
  446.         pos = how.adcr[sensor] * factor;
  447.         nextpoint = f(pos);
  448. }
  449. .DE
  450. .NH 2
  451. What Happens on Interrupt
  452. .PP
  453. In order to provide for parallel processing in the vax and
  454. in the lsi11, the following scheduling occurs:
  455. .TS
  456. allbox, tab(@);
  457. c c c.
  458.                         @LSI                    @VAX
  459. Interrupt Time -->      @gather arm state       @may still be computing
  460.                         @interrupt vax          @acknowledge
  461.                         @send buffer            @get buffer
  462.                         @wait for vax           @call user's fn1
  463.                         @                       @set up command buffer
  464.                         @get commands           @send command buffer
  465.                         @execute commands       @call user's fn2
  466. .TE
  467. .PP
  468. Three schemes are possible.
  469. The first one spreads the computations among fn1 and fn2.
  470. It is used to provide the fastest response to sensing feedback,
  471. while providing the maximum computing time.
  472. The second case only uses fn2 and provides the maximum computing time.
  473. The third case provides for best control if the computing time is
  474. short by using fn1 only.
  475. At the first interaction, fn1 is not called.
  476. .NH
  477. Examples
  478.  
  479. The Marsh-mallow Program :
  480. .PP
  481. This program merely reads the actual positions of the joints at time $t$
  482. and drive them at time $t+1$ with the read values.
  483. If a torque is exerted on a joint when the positions are measured,
  484. the actual position is:
  485. .EQ
  486. P sub a ~=~ P sub d ~+~ E
  487. .EN
  488. .PP
  489. Where $P sub a$ is the measured position, $P sub d$ is the desired
  490. position, and $E$ the position servo error.
  491. One can assume that the error is proportional to the exerted torque.
  492. .EQ
  493. E~=~k~T
  494. .EN
  495. Where $k$ is a spring constant depending on the gain of the servo and
  496. the sample rate.
  497. $T$ is the exerted torque.
  498. Let us compute the velocity by subtracting the differential position
  499. between two successive sample times when the actual position at
  500. time $t$ is specified as desired position at time $t+1$.
  501. .EQ
  502. P sub a sub {t+1} ~=~ P sub a sub {t}~+~ k~T sub {t+1}
  503. .EN
  504. .EQ
  505. DELTA P sub a ~=~ P sub a sub {t+1} - P sub a sub {t} ~=~ k~T sub {t}
  506. .EN
  507. .PP
  508. The velocity is proportional to the torque which make the manipulator
  509. act like a highly damped free system.
  510. .DS L
  511. #include "rtc.h"
  512.  
  513. int     enough = NO;
  514.  
  515. main()
  516. {
  517.         extern int terminate;
  518.         int dummy(), soft();
  519.  
  520.         control(dummy, soft);
  521.         printf("press return to end ");
  522.         getchar();
  523.         enough = YES;
  524.         while (!terminate)
  525.                 sleep(1);
  526.         release("done");
  527. }
  528.  
  529.  
  530. dummy()
  531. {
  532. }
  533.  
  534.  
  535. soft()
  536. {
  537.         extern struct chg chg;
  538.         extern struct how how;
  539.         register int i;
  540.  
  541.         if (enough) {
  542.                 terminate = YES;
  543.                 return;
  544.         }
  545.         chg.a_motion.set = POS;
  546.         for (i = 0; i < NJOINTS; ++i) {
  547.                 chg.a_motion.vala[i] = how.pos[i];
  548.         }
  549. }
  550. .DE
  551. The Free Program :
  552. .PP
  553. This second example makes use of the torques to motor currents mapping
  554. to overcome the gravity loadings of the manipulator joints.
  555. .DS L
  556. #include "rtc.h"
  557.  
  558. extern struct how how;
  559. extern struct chg chg;
  560.  
  561. main()
  562. {
  563.         extern int terminate;
  564.         int dummy(), freej();
  565.  
  566.         control(dummy, freej);
  567.         for (; ; ) {
  568.                 pause();
  569.         }
  570. }
  571.  
  572. dummy(){}
  573.  
  574. static freej()
  575. {
  576.         double sin(), cos();
  577.  
  578.         static int first = YES;
  579.         static unsigned short old[NJOINTS];
  580.         short cur[NJOINTS];
  581.         double jpos[NJOINTS], gtor[NJOINTS];
  582.         double c2, c23, s23, c4, s4, c5, s5;
  583.         register int i;
  584.  
  585.         if (first) {
  586.                 first = NO;
  587.                 for (i = 0; i < NJOINTS; ++i) {
  588.                         old[i] = how.pos[i];
  589.                 }
  590.                 return;
  591.         }
  592.         enctoang(jpos, how.pos);
  593.         c2 = cos(jpos[1]);
  594.         c23 = cos(jpos[1] + jpos[2]);
  595.         s23 = sin(jpos[1] + jpos[2]);
  596.         c4 = cos(jpos[3]);
  597.         s4 = sin(jpos[3]);
  598.         c5 = cos(jpos[4]);
  599.         s5 = sin(jpos[4]);
  600.         gravload(gtor, c2, c23, s23, c4, s4, c5, s5);
  601.         tortodac(cur, gtor, how.pos, old);
  602.         for (i = 0; i < NJOINTS; ++i) {
  603.                 chg.a_motion.vala[i] = cur[i];
  604.                 old[i] = how.pos[i];
  605.         }
  606.         chg.a_motion.set = CUR;
  607. }
  608.  
  609.  
  610. gravload(l, c2, c23, s23, c4, s4, c5, s5)
  611. double *l;
  612. double c2, c23, s23, c4, s4, c5, s5;
  613. {
  614.         l[0] = 0.;
  615.         l[2] = CP32 * s23 + CP31 * c23;
  616.         l[1] = l[2] + CP21 * c2;
  617.         l[3] = -(CP50 * s23 * s4 * s5);
  618.         l[4] = CP50 * (s23 * c4 * c5 + c23 * s5);
  619.         l[5] = 0.;
  620. }
  621.  
  622. .DE
  623. .NH
  624. Calibration, stepping mode, and automatic home return
  625. .PP
  626. It is time to insist on the fact that when the controller is
  627. powered up, the encoders counters contain random values that have
  628. no relation with the physical configuration of the arm.
  629. At least once after powering up the controller, the arm
  630. .B has
  631. to be calibrated.
  632. This is achieved by calling
  633. .B stepmode()
  634. before doing anything.
  635. When you exit from this mode, you are prompted for calibration.
  636. The arm must then it a position close to the home position.
  637. The calibration moves each joint if the arm, reset the counters
  638. and move each joint again to the home position.
  639. You must do it at least once, and in whichever configuration
  640. you could leave the arm,
  641. it is not necessary to do it before the next power up.
  642. If your program terminates leaving the arm away from its
  643. home position, you can either bring it back using the stepping
  644. mode and calibrate it again, or merely break any program at any point
  645. which cause the package to prompt you if you want
  646. an automatic home return.
  647. The return will be always successful, unless you seriously damaged
  648. the arm.
  649. .PP
  650. The ARM POWER switch is the only physical communication that the
  651. controller has with the rest of the universe.
  652. The sequence of operation is always the same :
  653.  
  654. .IP 1
  655. Power is off and the controller keeps monitoring the ARM POWER button;
  656. .IP 2
  657. You run you program, it can then open files, do system calls etc.
  658. It can either :
  659. .RS
  660. .IP 2.1
  661. exit.
  662. .IP 2.2
  663. call
  664. .B stepmode;
  665. .IP 2.3
  666. call
  667. .B control;
  668. .RE
  669. .IP 3
  670. The channel is opened, and the vax is waiting for interrupts.
  671. You press ARM POWER, and the controller starts interrupting the vax.
  672. .IP 4
  673. The vax receives interrupts and executes one of the three programs :
  674. .RS
  675. .IP 4.1
  676. If you are in stepping mode, you can move individually each joint,
  677. when done, the channel is closed;
  678. .IP 4.2
  679. If you asked for home return after a break, the arm will return and the whole
  680. programs exits.
  681. .IP 4.3
  682. Otherwise, your program issued a call to
  683. .B control
  684. and your
  685. interrupt functions are executed.
  686. When your program is done, it must call
  687. .B release;
  688. .RE
  689. .IP 5
  690. The channel is closed, goto step 1.
  691.  
  692. .PP
  693. You can code an unlimited number of 'control-release' pairs, if you need
  694. either to use different interrupt functions or perform system calls
  695. at a given moment.
  696. .PP
  697. The interface constantly monitors if the arm power is on.
  698. If for any reason, the arm power is turned off, the controller
  699. will still continue to run, but the vax will ignore interrupts
  700. and the arm will remains in the state it was at the moment
  701. power was turned off (and brakes set).
  702. Turning on the arm power again, will resume the execution.
  703. This may cause some jerky motions if the arm was
  704. stopped in the middle of a trajectory.
  705. .NH
  706. Error handling
  707. .PP
  708. The problem is to cleanly terminate a program when something
  709. goes wrong.
  710. If the error is detected in the main program, a proper exit at any place
  711. in the code can be :
  712. .DS L
  713.         if (panic) {
  714.                 terminate = YES;
  715.                 release("why ...");
  716.                 exit(1);
  717.         }
  718. .DE
  719. If the error is detected in the interrupt functions,
  720. .B release
  721. and
  722. .B exit
  723. cannot be called but
  724. .B terminate
  725. can be set and
  726. the interrupt function must return (in this case from interrupt).
  727. The package will cease to execute your interrupt functions.
  728. The main program remains active, arm power is turned off and
  729. everything seems frozen.
  730. The only resource is then to break the program
  731. and perform an automatic home position return
  732. if you wish.
  733. The string to which the
  734. .B mess
  735. variable is pointing to will
  736. be printed before the final exit. This is the only debugging
  737. tool in the real-time environment.
  738. Attention !, if the error is detected inside a function called
  739. from the main interrupt function, caution must be taken to
  740. cause a cascade of returns.
  741. The following shows a few possibilities.
  742. .DS L
  743. fn()    /* interrupt function */
  744. {
  745. /* do whatever */
  746.         if (panic) {
  747.                 mess = "why ...";
  748.                 terminate = YES;
  749.                 return;
  750.         }
  751. /* do whatever */
  752.         if (fn1())
  753.                 return;
  754. /* do whatever */
  755.         fn2();
  756.         if (terminate)
  757.                 return;
  758. }
  759.  
  760. fn1()
  761. {
  762. /* do whatever */
  763.         if (panic) {
  764.                 terminate = YES;
  765.                 mess = "why ...";
  766.                 return(YES);
  767.         }
  768. /* do whatever */
  769.         fn2();
  770.         if (terminate)
  771.                 return(YES);
  772. /* do whatever */
  773.         return(NO);
  774. }
  775.  
  776. fn2()
  777. {
  778. /* do whatever */
  779.         if (panic) {
  780.                 terminate = YES;
  781.                 mess = "why ...";
  782.                 return;
  783.         }
  784. /* do whatever */
  785. }
  786. .DE
  787. .PP
  788. Any message issued by the package is preceded by two stars, ex:
  789. "** Channel opened, turn on ARM POWER", so you can distinguish them from your
  790. own messages.
  791. .PP
  792. The package also performs checks on the validity of the
  793. data send to and received from the controller.
  794. Following is a list of all the messages:
  795. .IP 1)
  796. Error messages :
  797. .RS
  798. .IP
  799. "** too many commands", this will occur there are more commands
  800. specified than the output buffer can contain.
  801. .IP
  802. "** too large position increment", this means that ,in position mode,
  803. one joint has been specified a value too far from the last read position.
  804. .IP
  805. "** out of range", means that a specified value would drive a joint
  806. out of range.
  807. .IP
  808. "** too much current", means that you specified too a large value in
  809. current mode.
  810. .IP
  811. "** too large observed current", a driving current is too high, probably
  812. because the arm ran into an obstacle in position mode.
  813. .IP
  814. "** too large observed velocity", the velocity resulting from incorrect
  815. current or position specifications is too high.
  816. .IP
  817. "** joint(s) out of range", the position resulting from incorrect
  818. current or position specifications drives the arm out of range.
  819. .IP
  820. "** channel not released", the channel has not been released before
  821. a reopen via 'control()'.
  822. .IP
  823. "** bad checksum", result of a hardware failure.
  824. .IP
  825. "** interrupt occurred before end of user function",
  826. result of too lengthy computations. Most of the time you will get :
  827. .IP
  828. "**** hardware failure", the channel cannot initialize.
  829. .IP
  830. "**** driver error...exch = %d\n", something wrong, number of exchanges.
  831. .IP
  832. "** can't gtty", if the tty could'nt be put in cbreak mode during
  833. the stepping mode.
  834. .RE
  835. .IP 2)
  836. Informative messages.
  837. .RS
  838. .IP
  839. "** Interrupted", when you break the program.
  840. .IP
  841. "** exch = %d", total number of times fn2 has been called.
  842. .IP
  843. "** end of step mode", self explanatory.
  844. .IP
  845. "** calibrating", while U wait for the arm to be calibrated.
  846. .IP
  847. "** attempting a home return", self explanatory.
  848. .IP
  849. "** back home, calibrated", ....
  850. .IP
  851. "** channel opened, turn on ARM POWER", informs that the vax is ready
  852. to receive interrupts.
  853. .RE
  854. .IP 3)
  855. Prompts
  856. .RS
  857. .IP
  858. "** attempt an automatic home return ?", what you get when the
  859. program is broken, answer `y' or `n'.
  860. .IP
  861. "** exit ? (y/n) _  calibrate ? (y/n) _  sure ? (y/n) _ ",
  862. exit of the stepping mode.
  863. .RE
  864. .NH
  865. Appendix
  866. .PP
  867. Additional entry points are provided :
  868.  
  869. .IP -
  870. .B
  871. enctoang(a, e)
  872. .R
  873. is a function whose first argument is an array of 'NJOINTS'
  874. .B doubles
  875. and whose second argument is an array of 'NJOINTS'
  876. .B shorts.
  877. The function converts the encoders values contained in the second
  878. argument to angles expressed in
  879. .B radians
  880. within the range [-$pi$ ,+$pi$] relative to
  881. the solution coordinate frames described in [Paul2 81] for the Puma
  882. arm and in [Paul3 81] for the Stanford arm.
  883.  
  884. .IP -
  885. .B
  886. angtoenc(e, a)
  887. .R
  888. is a function which performs the inverse transformation.
  889. The first argument is an array of 'NJOINTS'
  890. .B shorts
  891. and the second
  892. argument is an array of 'NJOINTS'
  893. .B doubles.
  894. This function returns a non zero integer code when one or more
  895. angle is out of range.
  896. The bits are referenced by their octal value.
  897. Bit 01 is set if joint 1 is out of range, bit 02 for joint 2, bit 04
  898. for joint 3, and so on.
  899.  
  900. .IP -
  901. .B
  902. enctorng(r, e) and rngtoenc(e, r)
  903. .R
  904. perform the same functions
  905. as above but angles are expressed in the [0 - range] interval.
  906. In that case, an angle is zero when the corresponding joints
  907. is at its limit position turning counterclockwise.
  908.  
  909. .IP -
  910. .B
  911. angtorng(r, a) and rngtoang(a, r)
  912. .R
  913. perform the mappings of
  914. angles to ranges and vice-versa. Both arguments are arrays
  915. of doubles.
  916.  
  917. .IP -
  918. .B
  919. tortodac(d, t, v, o)
  920. .R
  921. performs torques to dac values mapping.
  922. Where 'd' is an array of 'NJOINTS'
  923. .B shorts,
  924. the resulting dac values, computed from the array 'd' of 'NJOINTS'
  925. .B doubles,
  926. the desired torques in
  927. .B N-mm.
  928. The arrays 'v' and 'o' are sets of 'NJOINTS'
  929. encoder values, 'v'
  930. is the current value of the joint positions, and 'o' the previous.
  931. This is needed to decide the current velocity of each joint [Zhang 83].
  932.  
  933. .IP -
  934. .B
  935. adctotor(t, a, v, o)
  936. .R
  937. performs the inverse operation, where 't' are
  938. the torques stored in an array of
  939. .B doubles
  940. computed from 'a' the measured adc values, an array of 'NJOINTS'
  941. .B shorts.
  942. The arrays 'v' and 'o' serve the same purpose as before.
  943.  
  944. .PP
  945. Memory allocation substitutes, work as described in Chap 2 of
  946. the UNIX manual, use :
  947. .TS
  948. tab(@);
  949. c c c.
  950. malloc_l @for @malloc
  951. free_l @for @free
  952. realloc_l @for @realloc
  953. calloc_l @for @calloc
  954. cfree_l @for @cfree
  955. .TE
  956. .EQ
  957. delim ^^
  958. .EN
  959. .NH
  960. Utility programs
  961. .PP
  962. A program called
  963. .B calib
  964. is made available, it contains :
  965. .DS L
  966. main()
  967. {
  968.         stepmode();
  969. }
  970. .DE
  971. It allows to calibrate the arm after power up, such as calling stepmode
  972. in the development programs is not mandatory.
  973. Use :
  974. .DS L
  975. calib
  976. .DE
  977. .PP
  978. A program called
  979. .B play
  980. reads a file of encoder values and ship them
  981. to the controller to be executed.
  982. Each setpoint is a record of seven 16 bits words.
  983. The first six words are the encoder values for the joints
  984. one through six.
  985. The seventh 16 bits word specifies the hand position.
  986. For historical reasons, it is expressed on the 12
  987. high order bits.
  988. With the pneumatic gripper, the character 'o' placed in those 12 bits,
  989. opens it, 'c' closes it.
  990. Play uses the file as a circular buffer and will play
  991. the sequence of points over and over.
  992. Both ends of the sequence must match.
  993. Use :
  994. .DS L
  995. play file
  996. .DE
  997. The programs promts : "more ? (y/n)", if 'n' is answered, the arm will
  998. stop at the end of the current cycle.
  999. If 'y' is answered, it becomes possible to change the rate at which
  1000. the points are send by factor of two.
  1001. .PP
  1002. The programs
  1003. .B mkenc
  1004. reads a file of points in formated form and
  1005. makes a file of 'playable' encoders values created as '@@@.out' in
  1006. the current directory.
  1007. The points must be expressed in
  1008. .B radians
  1009. relative to the solution coordinate
  1010. frames (it uses 'angtoenc').
  1011. An error message is printed on the standard error file each time
  1012. a value is specified closer than five degrees off the joint limits.
  1013. Use :
  1014. .DS L
  1015. mkenc file    or     mkenc < file
  1016. .DE
  1017. where "file" contains lines like :
  1018. .DS L
  1019. 0.00 -1.57 3.14 0 1.57 0
  1020. 0.00 -1.57 3.14 0 1.57 0
  1021. 0.00 -1.57 3.14 0 1.57 0
  1022. 0.00 -1.57 3.14 0 1.57 0
  1023. .DE
  1024. .PP
  1025. The shell file
  1026. .B dl
  1027. performs the downloading of the superviser
  1028. down to the controller, use :
  1029. .DS L
  1030. dl moper
  1031. .DE
  1032. for the Puma.
  1033. .PP
  1034. One more detail, a file called 'llib-rtc'
  1035. in the style of 'llib-lc' describes the
  1036. form of the calls and external variables.
  1037. This can be used for 'linting' your programs and checking the proper
  1038. list of arguments.
  1039. Use :
  1040. .DS L
  1041. lint myprog.c -v llib-rtc
  1042. .DE
  1043. where 'llib-rtc' may have to be preceded
  1044. by some leading path (see below).
  1045. .PP
  1046. Finally, use the math library '-lnm' for efficiency.
  1047. .NH
  1048. Files
  1049. .PP
  1050. Currently are set up for the Puma manipulator :
  1051. .DS L
  1052. /b/rccl/l/rtc.a         the library
  1053. /b/rccl/h/rtc.h         the include file
  1054. /b/rccl/l/llib-rtc      lint description of the library
  1055. /b/rccl/s/calib         calibration program (merely a call to stepmode)
  1056. /b/rccl/s/play          the play program
  1057. /b/rccl/s/mkenc         make encoder values
  1058. /b/rccl/s/dl            down load the controller
  1059. /b/rccl/s/moper         the superviser
  1060. .DE
  1061. .PP
  1062. In order to save typing errors there are some usefull short hands
  1063. to specify the leading paths.
  1064. As an example we list here the commands necessary to compile, link
  1065. and execute a real time program.
  1066. We will first set the PATH shell variable such as the list
  1067. of search directories also include '/b/rccl/s' (this can be done in
  1068. the '.profile' or '.cshrc' startup files) :
  1069. .DS L
  1070. PATH=$PATH:/b/rccl/s            (for sh users)
  1071. export PATH
  1072.  
  1073. set path=($path /b/rccl/s)      (for csh users)
  1074. .DE
  1075. We can know use
  1076. .B calib,
  1077. .B play,
  1078. and
  1079. .B dl
  1080. as regular commands.
  1081. .PP
  1082. Then we may like to create shell variables to specify the libraries (
  1083. can be done in '.profile' or '.cshrc').
  1084. .DS L
  1085. rtc=/b/rccl/l/rtc.a             (for sh users)
  1086. rtclint="-v /b/rccl/l/llib-rtc"
  1087.  
  1088. set rtc=/b/rccl/l/rtc.a         (for csh users)
  1089. set rtclint=(-v /b/rccl/l/llib-rtc)
  1090. .DE
  1091. .PP
  1092. The last detail is to specify the include files :
  1093. .DS L
  1094. rtc="-I/b/rccl/h /b/rccl/l/rtc.a"       (for sh users)
  1095. rtclint="-I/b/rccl/h -v /b/rccl/l/llib-rtc"
  1096.  
  1097. set rtc=(-I/b/rccl/h /b/rccl/l/rtc.a)        (for csh users)
  1098. set rtclint=(-I/b/rccl/h -v /b/rccl/l/llib-rtc)
  1099. .DE
  1100. Now the compile and link can be done as :
  1101. .DS L
  1102. cc myprog.c $rtc -lnm
  1103. .DE
  1104. and the lint :
  1105. .DS L
  1106. lint myprog.c $rtclint
  1107. .DE
  1108. If the controller has been downloaded and the arm calibrated, just type :
  1109. .DS L
  1110. a.out
  1111. .DE
  1112. When you get the message "** channel opened, turn on ARM POWER",
  1113. turn on ARM POWER and good luck.
  1114. .NH
  1115. References
  1116. .IP
  1117. Paul , R., P., Shimano, B. , Mayer, E., G.,
  1118. "Kinematic Control Equations for Simple Manipulators",
  1119. IEEE Transactions on Systems, Man, and Cybernetics, Vol. SMC-11,
  1120. No 6, June 1981.
  1121. .IP
  1122. Paul, R. P., "Robot Manipulators: Mathematics, Programming,
  1123. and Control", MIT Press 1981.
  1124. .IP
  1125. Zhang, H., Paul, R. P.,
  1126. "Determination of Simplified Dynamics of Puma Manipulator", Purdue University.
  1127.