Nclient.h
Go to the documentation of this file.
00001 /*
00002  * Nclient.h
00003  *
00004  * Interface file for direct connections to the robot or for
00005  * connections to Nserver.
00006  * 
00007  * Copyright 1991-1998, Nomadic Technologies, Inc.
00008  *
00009  */
00010 
00011 /* $Header: /home/cvs/host/client/Nclient.h,v 1.29 1999/07/22 17:53:20 rak Exp $ */
00012 
00013 #ifndef _HOST_CLIENT_NCLIENT_H_
00014 #define _HOST_CLIENT_NCLIENT_H_
00015 
00016 #ifdef __cplusplus
00017 extern "C" {
00018 #endif
00019 
00020 /* constants */
00021 
00022 #ifndef FALSE
00023 #define FALSE                   0
00024 #endif
00025 #ifndef TRUE
00026 #define TRUE                    1
00027 #endif
00028 #ifndef NULL
00029 #define NULL                    0
00030 #endif
00031 #define MAX_VERTICES     10
00032 #define NUM_STATE        45
00033 #define NUM_MASK         44 
00034 #define NUM_LASER        482 
00035 #define BUFSIZE          4096
00036 #define MAX_USER_BUF     0xFFFF
00037 
00038 /* Robot models. */
00039 #define MODEL_N200   0
00040 #define MODEL_N150   1
00041 #define MODEL_SCOUT  2
00042 #define MODEL_SCOUT2 2
00043 
00044 /* the number of sonars and infrareds */
00045 #define SONARS           16
00046 #define INFRAREDS        16
00047 
00048 /*
00049  * The following defines allow you to access the State vector in a 
00050  * more readable way.
00051  */
00052 
00053 #define STATE_SIM_SPEED            0
00054 
00055 #define STATE_IR_0                 1
00056 #define STATE_IR_1                 2
00057 #define STATE_IR_2                 3
00058 #define STATE_IR_3                 4
00059 #define STATE_IR_4                 5
00060 #define STATE_IR_5                 6
00061 #define STATE_IR_6                 7
00062 #define STATE_IR_7                 8
00063 #define STATE_IR_8                 9
00064 #define STATE_IR_9                 10
00065 #define STATE_IR_10                11
00066 #define STATE_IR_11                12
00067 #define STATE_IR_12                13
00068 #define STATE_IR_13                14
00069 #define STATE_IR_14                15
00070 #define STATE_IR_15                16
00071 
00072 #define STATE_SONAR_0              17
00073 #define STATE_SONAR_1              18
00074 #define STATE_SONAR_2              19
00075 #define STATE_SONAR_3              20
00076 #define STATE_SONAR_4              21
00077 #define STATE_SONAR_5              22
00078 #define STATE_SONAR_6              23
00079 #define STATE_SONAR_7              24
00080 #define STATE_SONAR_8              25
00081 #define STATE_SONAR_9              26
00082 #define STATE_SONAR_10             27
00083 #define STATE_SONAR_11             28
00084 #define STATE_SONAR_12             29
00085 #define STATE_SONAR_13             30
00086 #define STATE_SONAR_14             31
00087 #define STATE_SONAR_15             32
00088  
00089 #define STATE_BUMPER               33
00090 #define STATE_CONF_X               34
00091 #define STATE_CONF_Y               35
00092 #define STATE_CONF_STEER           36
00093 #define STATE_CONF_TURRET          37
00094 #define STATE_VEL_TRANS            38
00095 #define STATE_VEL_RIGHT            38   /* for scout */
00096 #define STATE_VEL_STEER            39
00097 #define STATE_VEL_LEFT             39   /* for scout */
00098 #define STATE_VEL_TURRET           40
00099 #define STATE_MOTOR_STATUS         41
00100 #define STATE_LASER                42
00101 #define STATE_COMPASS              43
00102 #define STATE_ERROR                44
00103 
00104 /*
00105  * The following defines allow you to access the Smask vector in a 
00106  * more readable way.
00107  */
00108 
00109 #define SMASK_POS_DATA             0
00110 
00111 #define SMASK_IR_1                 1
00112 #define SMASK_IR_2                 2
00113 #define SMASK_IR_3                 3
00114 #define SMASK_IR_4                 4
00115 #define SMASK_IR_5                 5
00116 #define SMASK_IR_6                 6
00117 #define SMASK_IR_7                 7
00118 #define SMASK_IR_8                 8
00119 #define SMASK_IR_9                 9
00120 #define SMASK_IR_10                10
00121 #define SMASK_IR_11                11
00122 #define SMASK_IR_12                12
00123 #define SMASK_IR_13                13
00124 #define SMASK_IR_14                14
00125 #define SMASK_IR_15                15
00126 #define SMASK_IR_16                16
00127 
00128 #define SMASK_SONAR_1              17
00129 #define SMASK_SONAR_2              18
00130 #define SMASK_SONAR_3              19
00131 #define SMASK_SONAR_4              20
00132 #define SMASK_SONAR_5              21
00133 #define SMASK_SONAR_6              22
00134 #define SMASK_SONAR_7              23
00135 #define SMASK_SONAR_8              24
00136 #define SMASK_SONAR_9              25
00137 #define SMASK_SONAR_10             26
00138 #define SMASK_SONAR_11             27
00139 #define SMASK_SONAR_12             28
00140 #define SMASK_SONAR_13             29
00141 #define SMASK_SONAR_14             30
00142 #define SMASK_SONAR_15             31
00143 #define SMASK_SONAR_16             32
00144  
00145 #define SMASK_BUMPER               33
00146 #define SMASK_CONF_X               34
00147 #define SMASK_CONF_Y               35
00148 #define SMASK_CONF_STEER           36
00149 #define SMASK_CONF_TURRET          37
00150 #define SMASK_VEL_TRANS            38
00151 #define SMASK_VEL_STEER            39
00152 #define SMASK_VEL_TURRET           40
00153 #define SMASK_RESERVED             41
00154 #define SMASK_LASER                42
00155 #define SMASK_COMPASS              43
00156 
00157 /*
00158  * These defines are used for specifying the control modes in the
00159  * robot motion command 'mv'. If MV_IGNORE is specified for an axis
00160  * the current motion command for it will remain active. Specifying
00161  * MV_VM or MV_PR will select velocity and position control as in 
00162  * the vm and pr robot motion commands 
00163  */
00164 
00165 #define MV_IGNORE 0
00166 #define MV_VM     1 /* velocity mode */
00167 #define MV_PR     2 /* position relative mode */
00168 #define MV_LP     3 /* limp mode */
00169 #define MV_AC     4 /* set acceleration for vm, pr, pa modes*/
00170 #define MV_SP     5 /* set velocity for pr, pa modes */
00171 #define MV_PA     6 /* position absolute mode */
00172 #define MV_TQ     7 /* torque mode */
00173 #define MV_MT     8 /* set maximum torque for vm, pr, pa, tq modes */
00174 
00175 /*
00176  * zeroing modes for arm
00177  */
00178 
00179 #define ZR_CHECK         1
00180 #define ZR_ORIENT        2
00181 #define ZR_NO_N_GRIPPER  4
00182 
00183 /* 
00184  * user packet constants for arm 
00185  */
00186 
00187 #define ARM_ZR 40
00188 #define ARM_WS 41
00189 #define ARM_MV 42
00190 
00191 /*
00192  * function prototypes for arm
00193  */
00194 long arm_mv(long l_mode, long l_v, long g_mode, long g_v);
00195 long arm_ws(short lift, short grip, long timeout, long *time_remain);
00196 long arm_zr(short mode);
00197 
00198 /*
00199  * For requesting the PosData the following defines should be used.
00200  * Each sensor has a bit, if it is set the pos-data is attached
00201  * when the sensory data is returned.
00202  */
00203 
00204 #define POS_NONE          ( 0 << 0 )
00205 #define POS_INFRARED      ( 1 << 0 )
00206 #define POS_SONAR         ( 1 << 1 )
00207 #define POS_BUMPER        ( 1 << 2 )
00208 #define POS_LASER         ( 1 << 3 )
00209 #define POS_COMPASS       ( 1 << 4 )
00210 
00211 /* 
00212  * these macros enable the user to determine if the pos-attachment
00213  * is requested for a specific sensor. 1 is returned if the 
00214  * attachment is requested, 0 otherwise
00215  * 
00216  * Note that the function posDataCheck() is called (see below)
00217  */
00218 
00219 #define POS_INFRARED_P  ( ( (posDataCheck()) & POS_INFRARED ) ? 1 : 0 )
00220 #define POS_SONAR_P     ( ( (posDataCheck()) & POS_SONAR    ) ? 1 : 0 )
00221 #define POS_BUMPER_P    ( ( (posDataCheck()) & POS_BUMPER   ) ? 1 : 0 )
00222 #define POS_LASER_P     ( ( (posDataCheck()) & POS_LASER    ) ? 1 : 0 )
00223 #define POS_COMPASS_P   ( ( (posDataCheck()) & POS_COMPASS  ) ? 1 : 0 )
00224 
00225 /*
00226  * The user will be able to call a function that fills out a 
00227  * list of position data for a specific sensor reading. 
00228  * To access the sensors in that structure the following defines 
00229  * should be used. They should also be used if data for a single
00230  * infrared sensor / sonar is requested.
00231  */
00232 
00233 #define POS_IR_1             0
00234 #define POS_IR_2             1
00235 #define POS_IR_3             2
00236 #define POS_IR_4             3
00237 #define POS_IR_5             4
00238 #define POS_IR_6             5
00239 #define POS_IR_7             6 
00240 #define POS_IR_8             7
00241 #define POS_IR_9             8
00242 #define POS_IR_10            9
00243 #define POS_IR_11           10
00244 #define POS_IR_12           11
00245 #define POS_IR_13           12
00246 #define POS_IR_14           13
00247 #define POS_IR_15           14
00248 #define POS_IR_16           15
00249 
00250 #define POS_SONAR_1          0
00251 #define POS_SONAR_2          1
00252 #define POS_SONAR_3          2
00253 #define POS_SONAR_4          3
00254 #define POS_SONAR_5          4
00255 #define POS_SONAR_6          5 
00256 #define POS_SONAR_7          6  
00257 #define POS_SONAR_8          7
00258 #define POS_SONAR_9          8
00259 #define POS_SONAR_10         9
00260 #define POS_SONAR_11        10
00261 #define POS_SONAR_12        11
00262 #define POS_SONAR_13        12
00263 #define POS_SONAR_14        13
00264 #define POS_SONAR_15        14
00265 #define POS_SONAR_16        15
00266 
00267 
00268 /* Define the length of the user buffer (Maximal short).
00269  * Due to Protocol bytes, the effective length is 65526 
00270  */
00271 #define USER_BUFFER_LENGTH      0xFFFF
00272 
00273 
00274 /* these definitions apply to the Scout and SuperScout */
00275 #define ROTATION_CONSTANT       0.118597  /* inches/degree (known to 100 ppm) */
00276 
00277 #define RIGHT(trans, steer)     (trans + (int)((float)steer*ROTATION_CONSTANT))
00278 #define LEFT(trans, steer)      (trans - (int)((float)steer*ROTATION_CONSTANT))
00279 
00280 #define scout_vm(trans, steer)  vm(RIGHT(trans, steer), LEFT(trans, steer), 0)
00281 
00282 /********************
00283  *                  *
00284  * Type definitions *
00285  *                  *
00286  ********************/
00287 
00288 /*
00289  * The following type definitions are used for the PosData.
00290  * PosData is an information packet that is attached to 
00291  * each sensor reading, if requested. Note that the use of 
00292  * PosData could cause compatibility problems when different
00293  * releases of the software are used on the robot and on the
00294  * server side. 
00295  *
00296  * The information packet can be used to determine how up-to-date
00297  * a sensory reading is. It contains the configuration of the robot.
00298  * This is the most updated configuration at the time of the sensor
00299  * reading. However, it is possible that the sensory reading
00300  * was taken after the integration of the coniguration.
00301  * To determine the interval that has passed two timestamps are in-
00302  * cluded in this information package: a timestamp for the computation
00303  * of the configuration and another timestamp for the actual capturing
00304  * of the senor reading.
00305  *
00306  * The timestamps are in milliseconds of the internal clock of the 
00307  * board that handles the sensors (Intellisys 100 sensor-board).
00308  */
00309 
00310 /*
00311  * TimeData contains the current time of the Intellisys 100 
00312  * in milliseconds
00313  */
00314 
00315 typedef unsigned long TimeData;
00316 
00317 /*
00318  * ConfigData is where the i486 writes the current configuration
00319  * of the robot, so that the Intellisys 100 can attach current
00320  * integration values to the sensor readings.
00321  * It is also used inside of the Pos data.
00322  */
00323 
00324 typedef struct _ConfigData
00325 {
00326     /* the configuration of the robot */
00327     long          configX;
00328     long          configY;
00329     long          configSteer;
00330     long          configTurret;
00331 
00332     /* the velocities of the robot*/
00333     long          velTrans;
00334     long          velSteer;
00335     long          velTurret;
00336 
00337     /* time of integration in milliseconds (Intellisys 100 time) */
00338     TimeData      timeStamp;
00339 
00340 } ConfigData;
00341 
00342 
00343 /* 
00344  * PosData contains information that is attached to a sensor
00345  * reading in order to determine how recent it is.
00346  */
00347 
00348 typedef struct _PosData
00349 {
00350     /* the configuration of the robot at the time of the reading */
00351     ConfigData config;
00352 
00353     /* the time of the sensing in milliseconds (Intellisys 100 time) */
00354     TimeData   timeStamp;
00355 
00356 } PosData;
00357 
00358 /* these type definitions are for user defined package processing */
00359 
00360 typedef union
00361 {
00362   char            bytes[8];
00363   double          data;
00364 } double_union;
00365 
00366 typedef union
00367 {
00368   char          bytes[4];
00369   short         words[2];
00370   long          data;
00371 } long_union;
00372 
00373 typedef union
00374 {
00375   unsigned char bytes[2];
00376   short         data;
00377 } short_union;
00378 
00379 typedef union
00380 {
00381   unsigned char   bytes[2];
00382   unsigned short  data;
00383 } ushort_union;
00384 
00385 typedef union
00386 {
00387   unsigned char bytes[4];
00388   unsigned short        words[2];
00389   unsigned long data;
00390 } ulong_union;
00391 
00392 struct request_struct
00393 {
00394   short type;
00395   unsigned short size;
00396   long  mesg[USER_BUFFER_LENGTH];
00397 };
00398 
00399 struct reply_struct
00400 {
00401   short type;
00402   unsigned short size;
00403   long  mesg[USER_BUFFER_LENGTH];
00404 };
00405 
00406 /********************
00407  *                  *
00408  * Global Variables *
00409  *                  *
00410  ********************/
00411 
00412 /* The State vector is an array of 45 long integers:
00413  *
00414  *   State[0] - stores actual simulation speed with 10 being realtime 
00415  *              (20 meaning twice as fast as realtime and 5 meaning half the 
00416  *              speed of realtime).
00417  *   State[1 ... 16] - stores the 16 infrared data.
00418  *   State[17 ... 32] - stores the 16 sonar data.
00419  *   State[33] - stores bumper data
00420  *   State[34 ... 37] - stores robot configuration
00421  *   State[38 ... 40] - stores robot's current velocities
00422  *   State[41] - motor status: the lowest bit is set to 1 if the translational
00423  *               motor is active; the second lowest bit is set to 1 if the 
00424  *               steering motor is active; the third lowest bit is set to 1 if 
00425  *               the turret motor is active.
00426  *   State[42] - laser mode: the mode of the laser.
00427  *   State[43] - compass value.
00428  *   State[44] - error number.
00429  */
00430 extern long State[NUM_STATE];
00431 
00432 /* The Smask vector is an array of 44 integers:
00433  *
00434  *   Smask[0] - used for the posData attachment to sensory data
00435  *   Smask[1 ... 16] - infrared mask
00436  *   Smask[17 ... 32] - sonar mask
00437  *   Smask[33] - bumper mask
00438  *   Smask[34 ... 37] - configuration mask
00439  *   Smask[38 ... 40] - velocity mask
00440  *   Smask[41] - irrelevant.
00441  *   Smask[42] - laser mask
00442  *   Smask[43] - compass mask
00443  */
00444 extern int Smask[NUM_MASK];
00445 
00446 /* Mask is now just a pointer to Smask. This is because Mask is a declared
00447  * variable in X11 library. So if you are not using X11, you can uncomment
00448  * the following line and keep using Mask as before. However, if you want
00449  * to use X11 graphic in your application program, you can simply use Smask
00450  * instead. 
00451  */
00452 /* static int *Mask = Smask; */
00453 
00454 /* The Laser vector is an array of 965 elements. The Laser vector
00455  * can contain laser data in one of the three formats: pixel, point, or line.
00456  *
00457  *    In pixel mode (not available in simulation, Laser[0] keeps the number of 
00458  *    pixels in the Laser vector. The can be a maximum of 482 pixels.
00459  *
00460  *    In point mode, Laser[0] keeps the number of points. Each point is 
00461  *    specified y the two numbers: the x and y coordinates of the point in 
00462  *    the robot's local coordinate. There can be a maximum of 482 points 
00463  *    (thus 964 numbers).
00464  *
00465  *    In line mode, Laser[0] keeps the number of lines. Each line segment is 
00466  *    specified by its two end points and each end point is specified by its 
00467  *    x and y coordinates in the robot's local coordinate. There can be a 
00468  *    maximum of 241 points. 
00469  */
00470 extern int Laser[2*NUM_LASER+1];
00471 
00472 /* If linking the application program with Nclient.o, it will connect 
00473  * to Nserver. To specify to which machine to connect and which port
00474  * to use the following variables can be redefined, otherwise default 
00475  * values are used:
00476  *     SERVER_MACHINE_NAME
00477  *     SERV_TCP_PORT
00478  *
00479  * If linking the application program with Ndirect.o, it will connect
00480  * directly to the robot. To specify to which robot to connect and
00481  * which parameters to use for the connection the following variables
00482  * can be redefined, otherwise default vaues are used:
00483  *     ROBOT_MACHINE_NAME
00484  * usually don't need to be changed:
00485  *     CONN_TYPE
00486  *     SERIAL_PORT
00487  *     SERIAL_BAUD
00488  *     ROBOT_TCP_PORT
00489  *
00490  * If an application program should run with Nclient.o and Ndirect.o
00491  * all of the above variables should be initialized.
00492  *
00493  * The concerend variables are define below.
00494  */
00495 
00496 /* SERVER_MACHINE_NAME is the name of the machine where the server is 
00497  * running. You should specify the server machine name in your
00498  * program if the server is running on a computer different from 
00499  * where the client is running 
00500  */
00501 extern char SERVER_MACHINE_NAME[80];
00502 
00503 /* SERV_TCP_PORT is an arbitrary port number the server listens to for 
00504  * request of connection. It should be the same as that specified in the 
00505  * world.setup file. You may modify this number and that in the world.setup 
00506  * file to allow multiple servers running on the same machine. 
00507  */
00508 extern int SERV_TCP_PORT;
00509 
00510 /* ROBOT_MACHINE_NAME is the name of the machine on the robot 
00511  */
00512 extern char ROBOT_MACHINE_NAME[80];
00513 
00514 /* CONN_TYPE is the selection between using a serial port or a TCP/IP port.
00515  * If set to 1, serial port is used.  If set to 2 (the default), TCP/IP port
00516  * is used.  If set to any other value, connection will fail.
00517  */
00518 extern int CONN_TYPE;
00519 
00520 /* SERIAL_PORT is a string containing the filename of the serial port you
00521  * choose to communicate to the robot on.  The default is "/dev/ttyS0".
00522  */
00523 extern char SERIAL_PORT[40];
00524 
00525 /* SERIAL_BAUD is the baud rate to set the serial communication to.  It
00526  * defaults to 9600.
00527  */
00528 extern int SERIAL_BAUD;
00529 
00530 /* ROBOT_TCP_PORT is the port number the robot listens on for request of
00531  * connection.  It defaults (and should always be set) to 65001 for the
00532  * standard binary port.
00533  */
00534 extern int ROBOT_TCP_PORT;
00535 
00536 /* LASER_CALIBRATION and LASER_OFFSET are the values that the laser
00537  * calibration software returns to you in the file Laser.cal, and that
00538  * are normally stored in the file robot.setup under [laser]calibration
00539  * and [laser]offset when Nserver is present.  Set these values with
00540  * the properly calculated values for your laser system if you have one.
00541  * This is only needed for linking with Ndirect.o. 
00542  */
00543 
00544 extern double LASER_CALIBRATION[8];
00545 extern double LASER_OFFSET[2];
00546 
00547 /*****************************
00548  *                           *
00549  * Robot Interface Functions *
00550  *                           *
00551  *****************************/
00552 
00553 /*
00554  * create_robot - requests the server to create a robot with
00555  *                id = robot_id and establishes a connection with
00556  *                the robot. This function is disabled in this
00557  *                version of the software.
00558  * 
00559  * parameters:
00560  *    long robot_id -- id of the robot to be created. The robot
00561  *                     will be referred to by this id. If a process
00562  *                     wants to talk (connect) to a robot, it must
00563  *                     know its id.
00564  */
00565 int create_robot(long robot_id);
00566 
00567 /*
00568  * connect_robot - requests the server to connect to the robot
00569  *                 with id = robot_id. In order to talk to the server,
00570  *                 the SERVER_MACHINE_NAME and SERV_TCP_PORT must be
00571  *                 set properly. If a robot with robot_id exists,
00572  *                 a connection is established with that robot. If
00573  *                 no robot exists with robot_id, no connection is
00574  *                 established.
00575  *
00576  * parameters:
00577  *    long robot_id -- robot's id. In this multiple robot version, in order
00578  *                     to connect to a robot, you must know it's id.
00579  *         model    -- robot type: 0 = Nomad 200, 1 = Nomad 150, 2 = Scout
00580  *         *dev     -- hostname for TCP, device file for serial ("/dev/" prefix
00581  *                     or ":" suffix means serial)
00582  *         conn     -- TCP port for TCP, baud rate for serial
00583  */
00584 int connect_robot(long robot_id, ...);
00585 
00586 /*
00587  * disconnect_robot - requests the server to close the connect with robot
00588  *                    with id = robot_id. 
00589  *
00590  * parameters:
00591  *    long robot_id -- robot's id. In order to disconnect a robot, you
00592  *                     must know it's id.
00593  */
00594 int disconnect_robot(long robot_id);
00595 
00596 /* 
00597  * ac - sets accelerations of the robot. Currently it has no effect in 
00598  *      simulation mode.
00599  *
00600  * parameters:
00601  *    int t_ac, s_ac, r_ac -- the translation, steering, and turret
00602  *                            accelerations. t_ac is in 1/10 inch/sec^2
00603  *                            s_ac and r_ac are in 1/10 degree/sec^2.
00604  */
00605 int ac(int t_ac, int s_ac, int r_ac);
00606 
00607 /*
00608  * sp - sets speeds of the robot, this function will not cause the robot to
00609  *      move. However, the set speed will be used when executing a pr()
00610  *      or a pa().
00611  *
00612  * parameters:
00613  *    int t_sp, s_sp, r_sp -- the translation, steering, and turret
00614  *                            speeds. t_sp is in 1/10 inch/sec and
00615  *                            s_sp and r_sp are in 1/10 degree/sec.
00616  */
00617 int sp(int t_sp, int s_sp, int r_sp);
00618 
00619 /*
00620  * pr - moves the motors of the robot by a relative distance, using the speeds
00621  *      set by sp(). The three parameters specify the relative distances for
00622  *      the three motors: translation, steering, and turret. All the three
00623  *      motors move concurrently if the speeds are not set to zero and the 
00624  *      distances to be traveled are non-zero. Depending on the timeout 
00625  *      period set (by function conf_tm(timeout)), the motion may 
00626  *      terminate before the robot has moved the specified distances
00627  *
00628  * parameters:
00629  *    int t_pr, s_pr, r_pr -- the specified relative distances of the
00630  *                            translation, steering, and turret motors.
00631  *                            t_pr is in 1/10 inch and s_pr and r_pr are
00632  *                            in 1/10 degrees.
00633  */
00634 int pr(int t_pr, int s_pr, int r_pr);
00635 
00636 /*
00637  * vm - velocity mode, command the robot to move at translational
00638  *      velocity = tv, steering velocity = sv, and rotational velocity =
00639  *      rv. The robot will continue to move at these velocities until
00640  *      either it receives another command or this command has been
00641  *      timeout (in which case it will stop its motion).
00642  *
00643  * parameters: 
00644  *    int t_vm, s_vm, r_vm -- the desired translation, steering, and turret
00645  *                            velocities. tv is in 1/10 inch/sec and
00646  *                            sv and rv are in 1/10 degree/sec.
00647  */
00648 int vm(int t_vm, int s_vm, int r_vm);
00649 
00650 /*
00651  * mv - move, send a generalized motion command to the robot.
00652  *      For each of the three axis (translation, steering, and
00653  *      turret) a motion mode (t_mode, s_mode, r_mode) can be 
00654  *      specified (using the values MV_IGNORE, MV_AC, MV_SP,
00655  *      MV_LP, MV_VM, and MV_PR defined above):
00656  *
00657  *         MV_IGNORE : the argument for this axis is ignored
00658  *                     and the axis's motion will remain 
00659  *                     unchanged.
00660  *         MV_AC :     the argument for this axis specifies
00661  *                     an acceleration value that will be used
00662  *                     during motion commands.
00663  *         MV_SP :     the argument for this axis specifies
00664  *                     a speed value that will be used during
00665  *                     position relative (PR) commands.
00666  *         MV_LP :     the arguemnt for this axis is ignored
00667  *                     but the motor is turned off.
00668  *         MV_VM :     the argument for this axis specifies
00669  *                     a velocity and the axis will be moved
00670  *                     with this velocity until a new motion
00671  *                     command is issued (vm,pr,mv) or 
00672  *                     recieves a timeout.
00673  *         MV_PR :     the argument for this axis specifies
00674  *                     a position and the axis will be moved
00675  *                     to this position, unless this command
00676  *                     is overwritten by another (vm,pr,mv).
00677  *
00678  * parameters: 
00679  *    int t_mode - the desired mode for the tranlation axis
00680  *    int t_mv   - the value for that axis, velocity or position,
00681  *                 depending on t_mode
00682  *    int s_mode - the desired mode for the steering axis
00683  *    int s_mv   - the value for that axis, velocity or position,
00684  *                 depending on t_mode
00685  *    int r_mode - the desired mode for the turret axis
00686  *    int r_mv   - the value for that axis, velocity or position,
00687  *                 depending on t_mode
00688  */
00689 int mv(int t_mode, int t_mv, int s_mode, int s_mv, int r_mode, int r_mv);
00690 
00691 /*
00692  * ct - send the sensor mask, Smask, to the robot. You must first change
00693  *      the global variable Smask to the desired communication mask before
00694  *      calling this function. 
00695  */
00696 int ct(void);
00697 
00698 /*
00699  * gs - get the current state of the robot according to the mask (of 
00700  *      the communication channel)
00701  */
00702 int gs(void);
00703 
00704 /*
00705  * st - stops the robot (the robot holds its current position)
00706  */
00707 int st(void);
00708 
00709 /*
00710  * lp - set motor limp (the robot may not hold its position).
00711  */
00712 int lp(void);
00713 
00714 /*
00715  * tk - sends the character stream, talk_string, to the voice synthesizer
00716  *      to make the robot talk.
00717  *
00718  * parameters:
00719  *    char *talk_string -- the string to be sent to the synthesizer.
00720  */
00721 int tk(char *talk_string);
00722 
00723 /*
00724  * dp - define the current position of the robot as (x,y)
00725  * 
00726  * parameters:
00727  *    int x, y -- the position to set the robot to.
00728  */
00729 int dp(int x, int y);
00730 
00731 /*
00732  * zr - zeroing the robot, align steering and turret with bumper zero.
00733  *      The position, steering and turret angles are all set to zero.
00734  *      This function returns when the zeroing process has completed.
00735  */
00736 int zr(void);
00737 
00738 /*
00739  * conf_ir - configure infrared sensor system.
00740  *
00741  * parameters: 
00742  *    int history -- specifies the percentage dependency of the current 
00743  *                   returned reading on the previous returned reading.
00744  *                   It should be set between 0 and 10: 0 = no dependency 
00745  *                   10 = full dependency, i.e. the reading will not change
00746  *    int order[16] --  specifies the firing sequence of the infrared 
00747  *                      (#0 .. #15). You can terminate the order list by a 
00748  *                      "255". For example, if you want to use only the 
00749  *                      front three infrared sensors then set order[0]=0,
00750  *                      order[1]=1, order[2]=15, order[3]=255 (terminator).
00751  */
00752 int conf_ir(int history, int order[16]);
00753 
00754 /*
00755  * conf_sn - configure sonar sensor system.
00756  *
00757  * parameters:
00758  *    int rate -- specifies the firing rate of the sonar in 4 milli-seconds 
00759  *                interval; 
00760  *    int order[16] -- specifies the firing sequence of the sonar (#0 .. #15).
00761  *                     You can terminate the order list by a "255". For 
00762  *                     example, if you want to use only the front three 
00763  *                     sensors, then set order[0]=0, order[1]=1, order[2]=15, 
00764  *                     order[3]=255 (terminator).
00765  */
00766 int conf_sn(int rate, int order[16]);
00767 
00768 /*
00769  * conf_cp - configure compass system.
00770  * 
00771  * parameters:
00772  *    int mode -- specifies compass on/off: 0 = off ; 1 = on; 2 = calibrate.
00773  *                When you call conf_cp (2), the robot will rotate slowly 360
00774  *                degrees. You must wait till the robot stops rotating before
00775  *                issuing another command to the robot (takes ~3 minutes).
00776  */
00777 int conf_cp(int mode);
00778 
00779 /*
00780  * conf_ls - configure laser sensor system:
00781  *
00782  * parameters:
00783  *    unsigned int mode -- specifies the on-board processing mode of the laser 
00784  *                         sensor data which determines the mode of the data 
00785  *                         coming back: 
00786  *                           the first bit specifies the on/off;
00787  *                           the second bit specifies point/line mode;
00788  *                           the third to fifth bits specify the 
00789  *                           returned data types: 
00790  *                             000 = peak pixel, 
00791  *                             001 = rise pixel, 
00792  *                             010 = fall pixel, 
00793  *                             011 = magnitude,
00794  *                             100 = distance;
00795  *                           the sixth bit specifies data integrity checking.
00796  *
00797  *   unsigned int threshold -- specifies the inverted acceptable brightness
00798  *                             of the laser line. 
00799  *
00800  *   unsigned int width -- specifies the acceptable width in terms
00801  *                         of number of pixels that are brighter than the 
00802  *                         set threshold.
00803  *  
00804  *   unsigned int num_data -- specifies the number of sampling points. 
00805  *   unsigned int processing --  specifies the number of neighboring 
00806  *                               pixels for averaging
00807  *
00808  * If you don't understand the above, try this one:
00809  *   conf_ls(51, 20, 20, 20, 4)
00810  */
00811 int conf_ls(unsigned int mode,
00812             unsigned int threshold,
00813             unsigned int width,
00814             unsigned int num_data,
00815             unsigned int processing);
00816 
00817 /*
00818  * conf_tm - sets the timeout period of the robot in seconds. If the
00819  *           robot has not received a command from the host computer
00820  *           for more than the timeout period, it will abort its 
00821  *           current motion
00822  * 
00823  * parameters:
00824  *    unsigned int timeout -- timeout period in seconds. If it is 0, there
00825  *                            will be no timeout on the robot.
00826  */
00827 int conf_tm(unsigned char timeout);
00828 
00829 /*
00830  * get_ir - get infrared data, independent of mask. However, only 
00831  *          the active infrared sensor readings are valid. It updates
00832  *          the State vector.
00833  */
00834 int get_ir(void);
00835 
00836 /*
00837  * get_sn - get sonar data, independent of mask. However, only 
00838  *          the active sonar sensor readings are valid. It updates
00839  *          the State vector.
00840  */
00841 int get_sn(void);
00842 
00843 /*
00844  * get_rc - get robot configuration data (x, y, th, tu), independent of 
00845  *          mask. It updates the State vector.
00846  */
00847 int get_rc(void);
00848 
00849 /*
00850  * get_rv - get robot velocities (translation, steering, and turret) data,
00851  *          independent of mask. It updates the State vector.
00852  */
00853 int get_rv(void);
00854 
00855 /*
00856  * get_ra - get robot acceleration (translation, steering, and turret) data,
00857  *          independent of mask. It updates the State vector.
00858  */
00859 int get_ra(void);
00860 
00861 /*
00862  * get_cp - get compass data, independent of mask. However, the
00863  *          data is valid only if the compass is on. It updates the
00864  *          State vector.
00865  */
00866 int get_cp(void);
00867 
00868 /*
00869  * get_ls - get laser data point mode, independent of mask. However the
00870  *          data is valid only of the laser is on. It updates the Laser 
00871  *          vector.
00872  */
00873 int get_ls(void);
00874 
00875 /*
00876  * get_bp - get bumper data, independent of mask. It updates the State
00877  *          vector.
00878  */
00879 int get_bp(void);
00880 
00881 /*
00882  * conf_sg - configure laser sensor system line segment processing mode:
00883  *
00884  * parameters:
00885  *    unsigned int threshold -- specifies the threshold value for least-square
00886  *                             fitting. When the error term grows above the 
00887  *                             threshold, the line segment will be broken
00888  *    unsigned int min_points -- specifies the acceptable number of points
00889  *                              to form a line segment.
00890  *    unsigned int gap -- specifies the acceptable "gap" between two segments
00891  *                        while they can still be treated as one (in 1/10 inch)
00892  *
00893  * If you don't understand the above, try this one:
00894  *    conf_sg(50, 4, 30)
00895  */
00896 int conf_sg(unsigned int threshold, 
00897             unsigned int min_points, 
00898             unsigned int gap);
00899 
00900 /*
00901  * get_sg - get laser data line mode, independent of mask. It updates
00902  *          the laser vector.
00903  */
00904 int get_sg(void);
00905 
00906 /*
00907  * da - define the current steering angle of the robot to be th
00908  *      and the current turret angle of the robot to be tu.
00909  * 
00910  * parameters:
00911  *    int th, tu -- the steering and turret orientations to set the
00912  *                  robot to.
00913  */
00914 int da(int th, int tu);
00915 
00916 /*
00917  * ws - waits for stop of motors of the robot. This function is intended  
00918  *      to be used in conjunction with pr() and pa() to detect the desired
00919  *      motion has finished
00920  *
00921  * parameters:
00922  *    unsigned char t_ws, s_ws, r_ws -- These three parameters specify 
00923  *                                      which axis or combination of axis 
00924  *                                      (translation, steering, and turret) 
00925  *                                      to wait. 
00926  *    unsigned char timeout -- specifies how long to wait before timing out 
00927  *                             (return without stopping the robot).
00928  */
00929 int ws(unsigned char t_ws, unsigned char s_ws,
00930        unsigned char r_ws, unsigned char timeout);
00931 
00932 /*
00933  * get_rpx - get the position of all nearby robots
00934  */
00935 int get_rpx(long *robot_pos);
00936 
00937 /*****************************
00938  *                           *
00939  * World Interface Functions *
00940  *                           *
00941  *****************************/
00942 
00943 /*
00944  * add_obstacle - creates an obstacle and adds it to the obstacle list
00945  *                of the robot environment. 
00946  * 
00947  * No effect in direct mode.
00948  * 
00949  * parameters:
00950  *    long obs[2*MAX_VERTICES+1] -- 
00951  *                The first element of obs specifies the number of 
00952  *                vertices of the polygonal obstacle (must be no greater 
00953  *                than MAX_VERTICES). The subsequent elements of obs 
00954  *                specifies the x and y coordinates of the vertices, 
00955  *                in counter-clockwise direction.
00956  */
00957 int add_obstacle(long obs[2*MAX_VERTICES+1]);
00958 
00959 /*
00960  * add_Obs - is the same as add_obstacle, for backward compatibility
00961  */
00962 int add_Obs(long obs[2*MAX_VERTICES+1]);
00963 
00964 
00965 /*
00966  * delete_obstacle - deletes an obstacle specified by obs from the robot 
00967  *                   environment 
00968  * parameters:
00969  *    long obs[2*MAX_VERTICES+1] -- 
00970  *                The first element of obs specifies the number of 
00971  *                vertices of the polygonal obstacle (must be no greater 
00972  *                than MAX_VERTICES). The subsequent elements of obs 
00973  *                specifies the x and y coordinates of the vertices, 
00974  *                in counter-clockwise direction.
00975  */
00976 int delete_obstacle(long obs[2*MAX_VERTICES+1]);
00977 
00978 /*
00979  * delete_Obs - is the same as delete_obstacle, for backward compatibility
00980  */
00981 int delete_Obs(long obs[2*MAX_VERTICES+1]);
00982 
00983 /*
00984  * move_obstacle - moves the obstacle obs by dx along x direction and 
00985  *                 dy along y direction. obs is modified.
00986  *
00987  * No effect in direct mode.
00988  * 
00989  * parameters:
00990  *    long obs[2*MAX_VERTICES+1] -- 
00991  *                The first element of obs specifies the number of 
00992  *                vertices of the polygonal obstacle (must be no greater 
00993  *                than MAX_VERTICES). The subsequent elements of obs 
00994  *                specifies the x and y coordinates of the vertices, 
00995  *                in counter-clockwise direction.
00996  *    long dx, dy -- the x and y distances to translate the obstacle
00997  */
00998 int move_obstacle(long obs[2*MAX_VERTICES+1], long dx, long dy);
00999 
01000 /*
01001  * move_Obs - is the same as move_obstacle, for backward compatibility
01002  *
01003  * No effect in direct mode.
01004  * 
01005  */
01006 int move_Obs(long obs[2*MAX_VERTICES+1], long dx, long dy);
01007 
01008 /*
01009  * new_world - deletes all obstacles in the current robot world
01010  *
01011  * No effect in direct mode.
01012  * 
01013  */
01014 int new_world(void);
01015 
01016 /****************************
01017  *                          *
01018  * Graphics refresh control *
01019  *                          *
01020  ****************************/
01021 
01022 /*
01023  * refresh_all - causes all temporary drawing in graphics window, including
01024  *               traces, sensors, and client graphics to be erased
01025  */
01026 int refresh_all(void);
01027 
01028 /*
01029  * refresh_all_traces - causes all robot traces in graphics to be erased
01030  */
01031 int refresh_all_traces(void);
01032 
01033 /*
01034  * refresh_actual_trace - causes actual robot trace in graphics to be erased
01035  */
01036 int refresh_actual_trace(void);
01037 
01038 /*
01039  * refresh_encoder_trace - causes encoder robot trace in graphics to be erased
01040  */
01041 int refresh_encoder_trace(void);
01042 
01043 /*
01044  * refresh_all_sensors - causes all sensor drawings in graphics to be erased
01045  */
01046 int refresh_all_sensors(void);
01047 
01048 /*
01049  * refresh_bumper_sensor - causes bumper drawings in graphics to be erased
01050  */
01051 int refresh_bumper_sensor(void);
01052 
01053 /*
01054  * refresh_infrared_sensor - causes infrared drawings in graphics to be erased
01055  */
01056 int refresh_infrared_sensor(void);
01057 
01058 /*
01059  * refresh_sonar_sensor - causes sonar drawings in graphics to be erased
01060  */
01061 int refresh_sonar_sensor(void);
01062 
01063 /*
01064  * refresh_laser_sensor - causes laser drawings in graphics to be erased
01065  */
01066 int refresh_laser_sensor(void);
01067 
01068 /*
01069  * refresh_client_graphics - causes drawings performed by any clients into
01070  *                           graphics window to be erased
01071  */
01072 int refresh_client_graphics(void);
01073 
01074 /*******************************
01075  *                             *
01076  * Miscellaneous robot control *
01077  *                             *
01078  *******************************/
01079 
01080 /*
01081  * init_mask - initialize the sensor mask, Smask.
01082  */
01083 void init_mask(void);
01084 
01085 /*
01086  * init_sensors - initialize the sensor mask, Smask, and send it to the
01087  *                robot. It has no effect on the sensors 
01088  */
01089 int init_sensors(void);
01090 
01091 /*
01092  * place_robot - places the robot at configuration (x, y, th, tu). 
01093  *               In simulation mode, it will place both the Encoder-robot
01094  *               and the Actual-robot at this configuration. In real robot
01095  *               mode, it will call dp(x, y) and da(th, tu).
01096  * 
01097  * parameters:
01098  *    int x, y -- x-y position of the desired robot configuration
01099  *    int th, tu -- the steering and turret orientation of the robot
01100  *                  desired configuration
01101  */
01102 int place_robot(int x, int y, int th, int tu);
01103 
01104 /*
01105  * special_request - sends a special request (stored in user_send_buffer) 
01106  *                   to the robot and waits for the robot's response (which
01107  *                   will be stored in user_receive_buffer). 
01108  * 
01109  * parameters:
01110  *    unsigned char *user_send_buffer -- stores data to be sent to the robot
01111  *                                       Should be a pointer to an array of
01112  *                                       1024 elements
01113  *    unsigned char *user_receive_buffer -- stores data received from the robot
01114  *                                          Should be a pointer to an array of 
01115  *                                          1024 elements
01116  */
01117 int special_request(unsigned char *user_send_buffer,
01118                     unsigned char *user_receive_buffer);
01119 
01120 /*******************************
01121  *                             *
01122  * Graphic Interface Functions *
01123  *                             *
01124  *******************************/
01125 
01126 /*
01127  * draw_robot - this function allows the client to draw a robot at
01128  *              configuration x, y, th, tu (using the robot world 
01129  *              coordinates). 
01130  * 
01131  * No effect in direct mode.
01132  * 
01133  * parameters:
01134  *    long x, y -- the x-y position of the robot.
01135  *    int th, tu -- the steering and turret orientation of the robot
01136  *    int mode - the drawing mode. If mode = 1, the robot is drawn in 
01137  *              BlackPixel using GXxor (using GXxor you can erase the trace 
01138  *              of robotby drawing over it). If mode = 2, the robot is 
01139  *              drawn in BlackPixel using GXxor and in addition, a small arrow
01140  *              is drawn at the center of the robot using GXcopy (using this 
01141  *              mode you can leave a trace of small arrow). If mode = 3, 
01142  *              the robot is drawn in BlackPixel using GXcopy. When mode > 3,
01143  *              the robot is drawn in color (GXxor) using color(mode-3), see
01144  *              Color table below.
01145  */
01146 int draw_robot(long x, long y, int th, int tu, int mode);
01147 
01148 
01149 /*
01150  * draw_line - this function allows the client to draw a line from
01151  *             (x_1, y_1) to (x_2, y_2) (using the robot world coordinates). 
01152  *
01153  * No effect in direct mode.
01154  * 
01155  * parameters:
01156  *    long x_1, y_1, x_2, y_2 -- the two end-points of the line
01157  *    int mode -- the mode of drawing: when mode is 1, the drawing is 
01158  *                done in BlackPixel using GXcopy; when mode is 2, the drawing
01159  *                is done in BlackPixel using GXxor, when mode > 2, the drawing
01160  *                is done in color (GXxor) using color(mode-2), see Color table
01161  *                below.
01162  */
01163 int draw_line(long x_1, long y_1, long x_2, long y_2, int mode);
01164 
01165 
01166 /*
01167  * draw_arc - this function allows the client to draw arc which is part
01168  *            of an ellipse (using the robot world coordinates). 
01169  *
01170  * No effect in direct mode.
01171  * 
01172  * parameters:
01173  *    long x_0, y_0, w, h -- (x_0, y_0) specifies the upper left corner of the 
01174  *                          rectangle bounding the ellipse while w and h
01175  *                          specifies the width and height of the bounding 
01176  *                          rectangle, respectively.
01177  *    int th1, th2 -- th1 and th2 specifies the angular range of the arc.
01178  *    int mode -- the mode of drawing: when mode is 1, the drawing is 
01179  *                done in BlackPixel using GXcopy; when mode is 2, the drawing
01180  *                is done in BlackPixel using GXxor, when mode > 2, the drawing
01181  *                is done in color (GXxor) using color(mode-2), see Color table
01182  *                below.
01183  */
01184 int draw_arc(long x_0, long y_0, long w, long h, int th1, int th2, int mode);
01185 
01186 /* 
01187  * Color table:
01188  *   color1             = Blue
01189  *   color2             = NavyBlue
01190  *   color3             = RoyalBlue
01191  *   color4             = SteelBlue
01192  *   color5             = CadetBlue
01193  *   color6             = Green
01194  *   color7             = SeaGreen
01195  *   color8             = ForestGreen
01196  *   color9             = DarkGreen
01197  *   color10            = LimeGreen
01198  *   color11            = Yellow
01199  *   color12            = Orange
01200  *   color13            = LightCoral
01201  *   color14            = DeepPink
01202  *   color15            = OrangeRed
01203  *   color16            = Red
01204  *   color17            = IndianRed
01205  *   color18            = VioletRed
01206  *   color19            = DeepPink
01207  *   color20            = Maroon
01208  */
01209 
01210 /*************************************
01211  *                                   *
01212  * Miscellaneous Interface Functions *
01213  *                                   *
01214  *************************************/
01215 
01216 /*
01217  * server_is_running - this function queries the server to see
01218  *                     if it is up and running.  If so, this function
01219  *                     returns a TRUE, otherwise it returns FALSE.
01220  *                     This function is replaced by connect_robot, but 
01221  *                     is defined here for backward compatibility
01222  *
01223  * No effect in direct mode.
01224  * 
01225  */
01226 int server_is_running(void);
01227 
01228 /*
01229  * quit_server - this function allows the client to quit the server
01230  *               assuming this feature is enabled in the setup file
01231  *               of the server
01232  *
01233  * No effect in direct mode.
01234  * 
01235  */
01236 int quit_server(void);
01237 
01238 /*
01239  * real_robot - this function allows the client to switch to
01240  *              real robot mode in the server
01241  *
01242  * No effect in direct mode.
01243  * 
01244  */
01245 int real_robot(void);
01246 
01247 /*
01248  * simulated_robot - this function allows the client to switch to
01249  *                   simulated robot mode in the server
01250  *
01251  * No effect in direct mode.
01252  * 
01253  */
01254 int simulated_robot(void);
01255 
01256 /*
01257  * predict_sensors - this function predicts the sensor reading of
01258  *                   the robot assuming it is at position (x, y)
01259  *                   and orientation th and tu using the map of the
01260  *                   simulated robot environment. The predicted sensor
01261  *                   data values are stored in "state" and "laser".
01262  * 
01263  * No effect in direct mode.
01264  * 
01265  * parameters:
01266  *    int x, y, th, tu -- the configuration of the robot
01267  *    long *state -- where to put the predicted state data
01268  *    int *laser -- where to put the predicted laser data
01269  */
01270 int predict_sensors(int x, int y, int th, int tu, long *state, int *laser);
01271 
01272 /* 
01273  * motion_check - this function computes the intersection of a path
01274  *                specified by the parameters: type, a1, ..., a7 with
01275  *                the obstacles in the robot's environment. If there is
01276  *                collision, the function returns 1 and the x-y configuration
01277  *                of the robot is stored in collide[0] and collide[1] while
01278  *                collide[2] stores the inward normal of the obstacle edge
01279  *                that the robot collides with (this information can be
01280  *                used to calculate which bumper is hit.). If there is no
01281  *                collision, the function returns 0.
01282  *
01283  * No effect in direct mode.
01284  * 
01285  * parameters:
01286  *    long type - 0 if the path is a line segment
01287  *                1 if the path is an arc of circle
01288  *    double a1 a2 - x-y coordinates of the first point of the path (the path
01289  *                   is directional).
01290  *    depending on the value of type, a3 - a7 have different meanings.
01291  *    if (type == 0), line segment mode
01292  *      double a3 a4 are the x-y coordinates of the second point of the path
01293  *      a5, a6, a7 have no meaning
01294  *    if (type == 1), arc of circle mode
01295  *      double a3 is the angle (in radiance) of the vector connecting the 
01296  *                center of the circle to the first end-point of the arc
01297  *      double a4 is the angle of the vector connecting the center
01298  *                of the circle to the second end-point of the arc
01299  *      double a5 is the radius of the circle
01300  *      double a6 a7 are the x-y coordinate of the center of the circle
01301  */
01302 int motion_check(long type, double a1, double a2, double a3, double a4, 
01303                  double a5, double a6, double a7, double collide[3]);
01304 
01305 /*
01306  * get_robot_conf - interactively getting the robot's conf, by clicking
01307  *                  the mouse in the server's Robot window
01308  * 
01309  * No effect in direct mode.
01310  * 
01311  * parameters:
01312  *    long *conf -- should be an array of 4 long integers. The configuration
01313  *                  of the robot is returned in this array.
01314  */
01315 int get_robot_conf(long *conf);
01316 
01317 /*******************************************
01318  *                                         *
01319  * The following are helper functions for  *
01320  * developing user defined host <-> robot  *
01321  * communication                           *
01322  *                                         *
01323  *******************************************/
01324 
01325 /*
01326  *  init_receive_buffer - sets the index to 4 which is the point
01327  *  at which data should begin to be extracted
01328  * 
01329  *  parameters:
01330  *     unsigned short *index -- is the buffer index
01331  */
01332 int init_receive_buffer(unsigned short *index);
01333 
01334 /*
01335  *  extract_receive_buffer_header - extracts the header information:
01336  *  length, serial_number, and packettype from the beginning of the
01337  *  receive buffer.
01338  *
01339  *  parameters:
01340  *     short *length -- is the returns the number of chars in the buffer
01341  *
01342  *     unsigned char *serial_number -- returns the serial number to be
01343  *                                     assigned to the packet
01344  *     unsigned char *packet_type -- returns the type number to be
01345  *                                   assigned to the packet
01346  *     unsigned char *buffer -- is the receive buffer
01347  */
01348 int extract_receive_buffer_header(unsigned short *length, 
01349                                   unsigned char *serial_number, 
01350                                   unsigned char *packet_type, 
01351                                   unsigned char *buffer);
01352 
01353 /*
01354  *  init_send_buffer - sets the index to 4 which is the point
01355  *  at which data should be inserted
01356  *
01357  *  parameters:
01358  *     unsigned short *index -- is the buffer index
01359  */
01360 int init_send_buffer(unsigned short *index);
01361 
01362 /*
01363  *  stuff_send_buffer_header - loads the header information,
01364  *  length,serial_number, and packettype into the beginning of the
01365  *  buffer.  It should be called after the data has been stuffed,
01366  *  i.e. index represents the length of the packet.
01367  *
01368  *  parameters:
01369  *     int index -- is the buffer index which holds the number of chars
01370  *                  in the buffer
01371  *     unsigned char serial_number -- holds the serial number to be
01372  *                                    assigned to the packet
01373  *     unsigned char packet_type -- holds the type number to be
01374  *                                 assigned to the packet
01375  *
01376  *     unsigned char *buffer -- is the send buffer
01377  */
01378 int stuff_send_buffer_header(unsigned short index, unsigned char serial_number, 
01379                              unsigned char packet_type, unsigned char *buffer);
01380 
01381 /*
01382  *  stuffchar -  stuffs a 1 byte char into the send buffer
01383  *
01384  *  parameters:
01385  *     signed char data -- is the char to be stuffed
01386  *     unsigned char *buffer -- is the send buffer
01387  *     unsigned short *index -- is the buffer index which will be incremented
01388  *                              to reflect the bytes stuffed into the buffer
01389  */
01390 int stuffchar(signed char data, unsigned char *buffer, unsigned short *index);
01391 
01392 /*
01393  *  stuff2byteint - stuffs a short int(2 bytes) into the send buffer
01394  *
01395  *  parameters:
01396  *     signed int data -- is the value which will be split apart and stuffed
01397  *                        bytewise into the send buffer
01398  *     unsigned char *buffer -- is the send buffer
01399  *     unsigned short *index -- is the buffer index which will be incremented
01400  *                              to reflect the bytes stuffed into the buffer
01401  */
01402 int stuff2byteint(signed short data,
01403                   unsigned char *buffer, unsigned short *index);
01404 
01405 /*
01406  *  stuff4byteint - stuffs a long int(4 bytes) into the send buffer
01407  *
01408  *  parameters:
01409  *     signed long data -- is the value which will be split apart and stuffed
01410  *                         bytewise into the send buffer
01411  *     unsigned char *buffer -- is the send buffer
01412  *     unsigned short *index -- is the buffer index which will be incremented
01413  *                              to reflect the bytes stuffed into the buffer
01414  */
01415 int stuff4byteint(signed long data,
01416                   unsigned char *buffer, unsigned short *index);
01417 
01418 /*
01419  *  stuffuchar -  stuffs an unsigned char into the send buffer
01420  *
01421  *  parameters:
01422  *     unsigned char data -- is the char to be stuffed
01423  *     unsigned char *buffer -- is the send buffer
01424  *     unsigned short *index -- is the buffer index which will be incremented
01425  *                              to reflect the bytes stuffed into the buffer
01426  */
01427 int stuffuchar(unsigned char data,
01428                unsigned char *buffer, unsigned short *index);
01429 
01430 /*
01431  *  stuff2byteuint - stuffs an unsigned short int(2 bytes) into the send buffer
01432  *
01433  *  parameters:
01434  *     unsigned short data -- is the value which will be split apart and 
01435  *                            stuffed bytewise into the send buffer
01436  *     unsigned char *buffer -- is the send buffer
01437  *     unsigned short *index -- is the buffer index which will be incremented
01438  *                              to reflect the bytes stuffed into the buffer
01439  */
01440 int stuff2byteuint(unsigned short data, unsigned char *buffer, unsigned short *index);
01441 
01442 /*
01443  *  stuff4byteuint - stuffs an unsigned long int(4 bytes) into the send buffer
01444  *
01445  *  parameters:
01446  *     unsigned long data -- is the value which will be split apart and stuffed
01447  *                           bytewise into the send buffer
01448  *     unsigned char *buffer -- is the send buffer
01449  *     unsigned short *index -- is the buffer index which will be incremented
01450  *                              to reflect the bytes stuffed into the buffer
01451  */
01452 int stuff4byteuint(unsigned long data, unsigned char *buffer, unsigned short *index);
01453 
01454 /*
01455  *  stuffdouble - stuffs a double(8 bytes) into the send buffer
01456  *
01457  *  parameters:
01458  *     double data -- is the value which will be split apart and stuffed
01459  *                    bytewise into the send buffer
01460  *     unsigned char *buffer -- is the send buffer
01461  *     unsigned short *index -- is the buffer index which will be incremented
01462  *                              to reflect the bytes stuffed into the buffer
01463  */
01464 int stuffdouble(double data, unsigned char *buffer, unsigned short *index);
01465 
01466 /*
01467  *  extractchar -  extracts a char from the receive buffer
01468  *
01469  *  parameters:
01470  *     unsigned char *buffer -- is the receive buffer which holds the data
01471  *     unsigned short *index -- is the receive buffer index which will be
01472  *                              incremented to reflect the position of the
01473  *                              next piece of data to be extracted
01474  */
01475 signed char extractchar(unsigned char *buffer, unsigned short *index);
01476 
01477 /*
01478  *  extract2byteint -  extracts a short int(2 bytes) from the receive buffer
01479  *
01480  *  parameters:
01481  *     unsigned char *buffer -- is the receive buffer which holds the data
01482  *     unsigned short *index -- is the receive buffer index which will be
01483  *                              incremented to reflect the position of the
01484  *                              next piece of data to be extracted
01485  */
01486 signed short extract2byteint(unsigned char *buffer, unsigned short *index);
01487 
01488 /*
01489  *  extract4byteint -  extracts a long int(4 bytes) from the receive buffer
01490  *
01491  *  parameters:
01492  *     unsigned char *buffer -- is the receive buffer which holds the data
01493  *     unsigned short *index -- is the receive buffer index which will be
01494  *                              incremented to reflect the position of the
01495  *                              next piece of data to be extracted
01496  */
01497 signed long extract4byteint(unsigned char *buffer, unsigned short *index);
01498 
01499 /*
01500  *  extractuchar -  extracts an unsigned char from the receive buffer
01501  *
01502  *  parameters:
01503  *     unsigned char *buffer -- is the receive buffer which holds the data
01504  *     unsigned short *index -- is the receive buffer index which will be
01505  *                              incremented to reflect the position of the
01506  *                              next piece of data to be extracted
01507  */
01508 unsigned char extractuchar(unsigned char *buffer, unsigned short *index);
01509 
01510 /*
01511  *  extract2byteuint -  extracts an unsigned short int(2 bytes) from the 
01512  *                      receive buffer
01513  *
01514  *  parameters:
01515  *     unsigned char *buffer -- is the receive buffer which holds the data
01516  *     unsigned short *index -- is the receive buffer index which will be
01517  *                              incremented to reflect the position of the
01518  *                              next piece of data to be extracted
01519  */
01520 unsigned short extract2byteuint(unsigned char *buffer, unsigned short *index);
01521 
01522 /*
01523  *  extract4byteuint -  extracts an unsigned long int(4 bytes) from the 
01524  *                      receive buffer
01525  *
01526  *  parameters:
01527  *     unsigned char *buffer -- is the receive buffer which holds the data
01528  *     unsigned short *index -- is the receive buffer index which will be
01529  *                              incremented to reflect the position of the
01530  *                              next piece of data to be extracted
01531  */
01532 unsigned long extract4byteuint(unsigned char *buffer, unsigned short *index);
01533 
01534 /*
01535  *  extractdouble -  extracts a double(8 bytes) from the receive buffer
01536  *
01537  *  parameters:
01538  *     unsigned char *buffer -- is the receive buffer which holds the data
01539  *     unsigned short *index -- is the receive buffer index which will be
01540  *                              incremented to reflect the position of the
01541  *                              next piece of data to be extracted
01542  */
01543 double extractdouble(unsigned char *buffer, unsigned short *index);
01544 
01545 /************************************************
01546  *                                              *
01547  * Global variable access functions for Allegro * 
01548  * Common Lisp interface                        *
01549  *                                              *
01550  ************************************************/
01551 
01552 int get_state(long state[NUM_STATE]);
01553 
01554 int get_laser(int laser[2*NUM_LASER+1]);
01555 
01556 int get_mask(int mask[NUM_MASK]);
01557 
01558 int set_mask(int mask[NUM_MASK]);
01559 
01560 int set_server_machine_name(char *sname);
01561 
01562 int set_serv_tcp_port(int port);
01563 
01564 
01565 /*************************************************
01566  *                                               *
01567  * Functions for the attachment of position      *
01568  * data to sensory readings.                     *
01569  *                                               *
01570  *************************************************/
01571 
01572 /***************
01573  * FUNCTION:     posDataRequest
01574  * PURPOSE:      request position information for sensors
01575  * ARGUMENTS:    int posRequest : 
01576  *               The argument of this function specifies the sensors 
01577  *               for which the position information (PosData) should 
01578  *               be attached to the sensory reading.
01579  *               Its value is obtained by ORing the desired defines. 
01580  * EXAMPLE:      To attach PosData to sonars and laser:
01581  *               posDataRequest ( POS_SONAR | POS_LASER );
01582  * ALGORITHM:    currently sets the global variable Smask[0] and
01583  *               then calls ct() to transmit the change to the server
01584  * RETURN:       TRUE if the argument was correct, else FALSE
01585  * SIDE EFFECT:  Smask[0]
01586  * CALLS:        
01587  * CALLED BY:    
01588  ***************/
01589 int posDataRequest ( int posRequest );
01590 
01591 
01592 /***************
01593  * FUNCTION:     posDataCheck
01594  * PURPOSE:      return the sensors for which the PosData attachment
01595  *               is currently requested. 
01596  * ARGUMENTS:    None
01597  * ALGORITHM:    returns the usedSmask that is not globally accessible
01598  *               (is set by ct() to be the value of Smask[0])
01599  * RETURN:       int, see posDataRequest
01600  *               the macros POS_*_P can be used to examine the value
01601  * SIDE EFFECT:  
01602  * CALLS:        
01603  * CALLED BY:    
01604  ***************/
01605 int posDataCheck ( void );
01606 
01607 
01608 /***************
01609  * FUNCTION:     posInfraredRingGet
01610  * PURPOSE:      copy the PosData for all infrareds to accessible memory
01611  * ARGUMENTS:    PosData posData [INFRAREDS] :
01612  *               an array of PosData structures that is filled with 
01613  *               PosData. The position information for each infrared
01614  *               containts the configuration of the robot at the time 
01615  *               of the sensory reading and a timestamp for the 
01616  *               configuration and the senosry reading .
01617  * ALGORITHM:    copies blocks of memory
01618  * RETURN:       int, return always TRUE
01619  * SIDE EFFECT:  
01620  * CALLS:        
01621  * CALLED BY:    
01622  ***************/
01623 int posInfraredRingGet ( PosData posData[INFRAREDS] );
01624 
01625 
01626 /***************
01627  * FUNCTION:     posInfraredGet
01628  * PURPOSE:      copy the PosData for a specific infrared to accessible 
01629  *               memory
01630  * ARGUMENTS:    PosData *posData : the memory location that the information
01631  *                                  will be copied to 
01632  *               int infraredNumber : the number of the infrared
01633  * ALGORITHM:    copies block of memory
01634  * RETURN:       int, always returns TRUE
01635  * SIDE EFFECT:  
01636  * CALLS:        
01637  * CALLED BY:    
01638  ***************/
01639 int posInfraredGet     ( PosData *posData , int infraredNumber );
01640 
01641 
01642 /***************
01643  * FUNCTION:     posSonarRingGet
01644  * PURPOSE:      copy the PosData for all sonars to accessible memory
01645  * ARGUMENTS:    PosData posData [SONARS] :
01646  *               an array of PosData structures that is filled with 
01647  *               PosData. The position information for each sonar
01648  *               containts the configuration of the robot at the time 
01649  *               of the sensory reading and a timestamp for the 
01650  *               configuration and the senosry reading .
01651  * ALGORITHM:    copies blocks of memory
01652  * RETURN:       int, return always TRUE
01653  * SIDE EFFECT:  
01654  * CALLS:        
01655  * CALLED BY:    
01656  ***************/
01657 int posSonarRingGet    ( PosData posData[SONARS] );
01658 
01659 
01660 /***************
01661  * FUNCTION:     posSonarGet
01662  * PURPOSE:      copy the PosData for a specific sonar to accessible memory
01663  * ARGUMENTS:    PosData *posData : the memory location that the information
01664  *                                  will be copied to 
01665  *                        int sonarNumber : the number of the sonar 
01666  * ALGORITHM:    copies block of memory
01667  * RETURN:       int, always returns TRUE
01668  * SIDE EFFECT:  
01669  * CALLS:        
01670  * CALLED BY:    
01671  ***************/
01672 int posSonarGet        ( PosData *posData , int sonarNumber );
01673 
01674 
01675 /***************
01676  * FUNCTION:     posBumperGet
01677  * PURPOSE:      copy PosData for the bumper to accessible memory
01678  * ARGUMENTS:    PosData *posData : where the data is copied to 
01679  * ALGORITHM:    copies a block of memory
01680  * RETURN:       int, always returns TRUE
01681  * SIDE EFFECT:  
01682  * CALLS:        
01683  * CALLED BY:    
01684  * NOTE:         The bumper differs from other sensors in that the 
01685  *               posData is only updated after one of the bumper sensors 
01686  *               change its value from zero to one. This means that the 
01687  *               posData for the bumper always contains the position and 
01688  *               timeStamps of the latest hit, or undefined information 
01689  *               if the bumper was not hit yet.
01690  ***************/
01691 int posBumperGet       ( PosData *posData );
01692 
01693 
01694 /***************
01695  * FUNCTION:     posLaserGet
01696  * PURPOSE:      copy PosData for the laser to accessible memory
01697  * ARGUMENTS:    PosData *posData : where the data is copied to 
01698  * ALGORITHM:    copies a block of memory
01699  * RETURN:       int, always returns TRUE
01700  * SIDE EFFECT:  
01701  * CALLS:        
01702  * CALLED BY:    
01703  * NOTE:         The laser is updated at a frequency of 30Hz.
01704  ***************/
01705 int posLaserGet        ( PosData *posData );
01706 
01707 
01708 /***************
01709  * FUNCTION:     posCompassGet
01710  * PURPOSE:      copy PosData for the compass to accessible memory
01711  * ARGUMENTS:    PosData *posData : where the data is copied to 
01712  * ALGORITHM:    copies a block of memory
01713  * RETURN:       int, always returns TRUE
01714  * SIDE EFFECT:  
01715  * CALLS:        
01716  * CALLED BY:    
01717  * NOTE:         The compass is updated ad a frequency of 10Hz.
01718  ***************/
01719 int posCompassGet      ( PosData *posData );
01720 
01721 
01722 /***************
01723  * FUNCTION:     posTimeGet
01724  * PURPOSE:      get the PosData time (Intellisys 100) in milliseconds
01725  * ARGUMENTS:    None
01726  * ALGORITHM:    ---
01727  * RETURN:       int 
01728  * SIDE EFFECT:  
01729  * CALLS:        
01730  * CALLED BY:    
01731  * NOTE:         The resolution of this timer is 16.4 milliseconds;
01732  *               the timer starts out at zero when the system is 
01733  *               turned on and will flow over after 49 days.
01734  ***************/
01735 int posTimeGet         ( void );
01736 
01737 
01738 /*************************************************
01739  *                                               *
01740  * Functions to determine the charge level       *
01741  * of the batteries for the cpu and the motors.  *
01742  *                                               *
01743  *************************************************/
01744 
01745 /***************
01746  * FUNCTION:     voltCpuGet
01747  * PURPOSE:      get the voltage of the power supply for the CPU
01748  * ARGUMENTS:    None
01749  * ALGORITHM:    ---
01750  * RETURN:       float (the voltage in volt)
01751  * SIDE EFFECT:  
01752  * CALLS:        
01753  * CALLED BY:    
01754  * NOTE:         This should never drop below 10.8 volts.
01755  ***************/
01756 float voltCpuGet       ( void );
01757 
01758 
01759 /***************
01760  * FUNCTION:     voltMotorGet
01761  * PURPOSE:      get the voltage of the power supply for the motors
01762  * ARGUMENTS:    None
01763  * ALGORITHM:    ---
01764  * RETURN:       float (the voltage in volt)
01765  * SIDE EFFECT:  
01766  * CALLS:        
01767  * CALLED BY:    
01768  * NOTE:         This should never drop below 10.8 volts.
01769  *               Returns average of the two motor batteries.
01770  ***************/
01771 float voltMotorGet     ( void );
01772 
01773 #ifdef __cplusplus
01774 }
01775 #endif
01776 
01777 #endif /* _HOST_CLIENT_NCLIENT_H_ */


scout_ndirect
Author(s): Gonçalo Cabrita and Pedro Sousa
autogenerated on Mon Jan 6 2014 11:25:23