#include <arpa/inet.h>
#include <fcntl.h>
#include <termios.h>
#include <signal.h>
#include <memory.h>
#include <errno.h>
#include <netdb.h>
#include <netinet/in.h>
#include <stdarg.h>
#include <stdio.h>
#include <unistd.h>
#include <sys/types.h>
#include <sys/socket.h>
#include <sys/time.h>
#include "Nclient.h"
Go to the source code of this file.
Classes | |
struct | _PosDataAll |
Defines | |
#define | AC 1 |
#define | ADD_OBS 32 |
#define | CONF_CP 16 |
#define | CONF_IR 14 |
#define | CONF_LS 17 |
#define | CONF_SER 35 |
#define | CONF_SG 28 |
#define | CONF_SN 15 |
#define | CONF_TM 18 |
#define | CONNECT_TIMEOUT 10 /* 10 seconds */ |
#define | CT 6 |
#define | DA 30 |
#define | DELETE_OBS 33 |
#define | DP 12 |
#define | GET_BP 27 |
#define | GET_CP 24 |
#define | GET_IR 19 |
#define | GET_LS 25 |
#define | GET_RA 23 |
#define | GET_RC 21 |
#define | GET_RV 22 |
#define | GET_SG 29 |
#define | GET_SN 20 |
#define | GS 7 |
#define | LONG_B(x, y, z, q) |
#define | LP 10 |
#define | MOVE_OBS 34 |
#define | MV 43 |
#define | NAK 8 |
#define | NORMAL_TIMEOUT 1 /* 1 second */ |
#define | NUM_COMMANDS 36 |
#define | PA 4 |
#define | PLACE_ROBOT 36 |
#define | POS_BUMPER_PI(x) ( ( (x) & POS_BUMPER ) ? 1 : 0 ) |
#define | POS_COMPASS_PI(x) ( ( (x) & POS_COMPASS ) ? 1 : 0 ) |
#define | POS_INFRARED_PI(x) ( ( (x) & POS_INFRARED ) ? 1 : 0 ) |
#define | POS_LASER_PI(x) ( ( (x) & POS_LASER ) ? 1 : 0 ) |
#define | POS_SONAR_PI(x) ( ( (x) & POS_SONAR ) ? 1 : 0 ) |
#define | PR 3 |
#define | RANGE_CPU_VOLTAGE 12.0 |
#define | RANGE_MOTOR_VOLTAGE 12.85 |
#define | RE_XMIT 0 /* not re-transmit when failed */ |
#define | SERIAL_OPEN_ERROR 1 |
#define | SERIAL_PKG_ERROR 4 |
#define | SERIAL_READ_ERROR 3 |
#define | SERIAL_TIMEOUT_ERROR 5 |
#define | SERIAL_WRITE_ERROR 2 |
#define | SETUP_LS 26 |
#define | SP 2 |
#define | SPECIAL 128 |
#define | SPECIAL_TIMEOUT 30 /* used for user define package */ |
#define | ST 9 |
#define | TK 11 |
#define | USER_BUFFER_LENGTH 0xFFFF |
#define | VM 5 |
#define | WS 31 |
#define | ZR 13 |
Typedefs | |
typedef struct _PosDataAll | PosDataAll |
Functions | |
int | ac (int t_ac, int s_ac, int r_ac) |
int | add_Obs (long obs[2 *MAX_VERTICES+1]) |
int | add_obstacle (long obs[2 *MAX_VERTICES+1]) |
long | arm_mv (long l_mode, long l_v, long g_mode, long g_v) |
long | arm_ws (short l, short g, long timeout, long *time_remain) |
long | arm_zr (short override) |
static unsigned char | bits_to_byte (char bt0, char bt1, char bt2, char bt3, char bt4, char bt5, char bt6, char bt7) |
static unsigned char | buf_fill (int fd, int conn_type) |
static long | combine_bumper_vector (unsigned char b1, unsigned char b2, unsigned char b3) |
static int | Comm_Robot (int fd, unsigned char command[BUFSIZE]) |
int | conf_cp (int mode) |
int | conf_ir (int history, int order[16]) |
int | conf_ls (unsigned int mode, unsigned int threshold, unsigned int width, unsigned int num_data, unsigned int processing) |
int | conf_ser (unsigned char port, unsigned short baud) |
int | conf_sg (unsigned int threshold, unsigned int min_points, unsigned int gap) |
int | conf_sn (int rate, int order[16]) |
int | conf_tm (unsigned char timeout) |
int | connect_robot (long robot_id,...) |
static void | convert_laser (int *laser) |
static char * | convertAddr (char *name, char *addr) |
int | create_robot (long robot_id) |
int | ct () |
int | da (int th, int tu) |
int | delete_Obs (long obs[2 *MAX_VERTICES+1]) |
int | delete_obstacle (long obs[2 *MAX_VERTICES+1]) |
int | disconnect_robot (long robot_id) |
int | dp (int x, int y) |
int | draw_arc (long x_0, long y_0, long w, long h, int th1, int th2, int mode) |
int | draw_line (long x_1, long y_1, long x_2, long y_2, int mode) |
int | draw_robot (long x, long y, int th, int tu, int mode) |
signed short | extract2byteint (unsigned char *buffer, unsigned short *index) |
unsigned short | extract2byteuint (unsigned char *buffer, unsigned short *index) |
signed long | extract4byteint (unsigned char *buffer, unsigned short *index) |
unsigned long | extract4byteuint (unsigned char *buffer, unsigned short *index) |
int | extract_receive_buffer_header (unsigned short *length, unsigned char *serial_number, unsigned char *packet_type, unsigned char *buffer) |
signed char | extractchar (unsigned char *buffer, unsigned short *index) |
double | extractdouble (unsigned char *buffer, unsigned short *index) |
unsigned char | extractuchar (unsigned char *buffer, unsigned short *index) |
int | get_bp () |
int | get_cp () |
int | get_ir () |
int | get_laser (int laser[2 *NUM_LASER+1]) |
int | get_ls () |
int | get_mask (int mask[NUM_MASK]) |
int | get_ra () |
int | get_rc () |
int | get_robot_conf (long *conf) |
int | get_rpx (long *robot_pos) |
int | get_rv () |
int | get_sg () |
int | get_sn () |
int | get_state (long state[NUM_STATE]) |
static unsigned char | GETC (int fd, int conn_type) |
int | gs () |
static int | high_half (unsigned char num) |
void | init_mask (void) |
int | init_receive_buffer (unsigned short *index) |
int | init_send_buffer (unsigned short *index) |
int | init_sensors () |
static int | low_half (unsigned char num) |
int | lp () |
int | motion_check (long type, double a1, double a2, double a3, double a4, double a5, double a6, double a7, double collide[3]) |
int | move_Obs (long obs[2 *MAX_VERTICES+1], long dx, long dy) |
int | move_obstacle (long obs[2 *MAX_VERTICES+1], long dx, long dy) |
int | mv (int t_mode, int t_mv, int s_mode, int s_mv, int r_mode, int r_mv) |
int | new_world (void) |
int | open_serial (char *port, unsigned short baud) |
int | pa (int t_pa, int s_pa, int r_pa) |
int | place_robot (int x, int y, int th, int tu) |
int | posBumperGet (PosData *posData) |
int | posCompassGet (PosData *posData) |
int | posDataCheck (void) |
int | posDataRequest (int posRequest) |
int | posInfraredGet (PosData *posData, int infraredNumber) |
int | posInfraredRingGet (PosData posData[INFRAREDS]) |
int | posLaserGet (PosData *posData) |
static long | posLongExtract (unsigned char *inbuf) |
static int | posPackageProcess (unsigned char *inbuf, PosData *posData) |
int | posSonarGet (PosData *posData, int sonarNumber) |
int | posSonarRingGet (PosData posData[SONARS]) |
int | posTimeGet (void) |
static unsigned long | posUnsignedLongExtract (unsigned char *inbuf) |
int | pr (int t_pr, int s_pr, int r_pr) |
int | predict_sensors (int x, int y, int th, int tu, long *state, int *laser) |
static void | Process_Acceleration_Pkg (unsigned char inbuf[BUFSIZE]) |
static void | Process_Bumper_Pkg (unsigned char inbuf[BUFSIZE]) |
static void | Process_Compass_Conf_Pkg (unsigned char inbuf[BUFSIZE]) |
static void | Process_Compass_Pkg (unsigned char inbuf[BUFSIZE]) |
static void | Process_Configuration_Pkg (unsigned char inbuf[BUFSIZE]) |
static void | Process_Infrared_Pkg (unsigned char inbuf[BUFSIZE]) |
static void | Process_Laser_Line_Pkg (unsigned char inbuf[BUFSIZE]) |
static void | Process_Laser_Point_Pkg (unsigned char inbuf[BUFSIZE]) |
static int | Process_Robot_Resp (unsigned char inbuf[BUFSIZE]) |
static void | Process_Sonar_Pkg (unsigned char inbuf[BUFSIZE]) |
static void | Process_Special_Pkg (unsigned char inbuf[BUFSIZE]) |
static void | Process_State_Pkg (unsigned char inbuf[BUFSIZE]) |
static void | Process_Velocity_Pkg (unsigned char inbuf[BUFSIZE]) |
static void | ProjectPhy (double xi1, double yi1, double *x, double *y) |
int | quit_server (void) |
static int | Read_Pkg (int fd, int conn_type, unsigned char *inbuf) |
int | real_robot (void) |
static int | serial_ready (int fd, int wait) |
int | server_is_running () |
int | set_mask (int mask[NUM_MASK]) |
int | set_serv_tcp_port (int port) |
int | set_server_machine_name (char *sname) |
static void | signed_int_to_two_bytes (int n, unsigned char *byte_ptr) |
int | simulated_robot (void) |
int | sp (int t_sp, int s_sp, int r_sp) |
int | special_request (unsigned char *user_send_buffer, unsigned char *user_receive_buffer) |
int | st () |
int | stuff2byteint (signed short data, unsigned char *buffer, unsigned short *index) |
int | stuff2byteuint (unsigned short data, unsigned char *buffer, unsigned short *index) |
int | stuff4byteint (signed long data, unsigned char *buffer, unsigned short *index) |
int | stuff4byteuint (unsigned long data, unsigned char *buffer, unsigned short *index) |
void | stuff_length_type (int length, int ptype, unsigned char *byte_ptr) |
int | stuff_send_buffer_header (unsigned short index, unsigned char serial_number, unsigned char packet_type, unsigned char *buffer) |
void | stuff_three_signed_int (int length, int ptype, int num1, int num2, int num3, unsigned char *byte_ptr) |
void | stuff_three_unsigned_int (int length, int ptype, int num1, int num2, int num3, unsigned char *byte_ptr) |
void | stuff_two_signed_int (int length, int ptype, int num1, int num2, unsigned char *byte_ptr) |
int | stuffchar (signed char data, unsigned char *buffer, unsigned short *index) |
int | stuffdouble (double data, unsigned char *buffer, unsigned short *index) |
int | stuffuchar (unsigned char data, unsigned char *buffer, unsigned short *index) |
static int | timePackageProcess (unsigned char *inbuf, unsigned long *timeS) |
int | tk (char *talk_string) |
static int | two_bytes_to_signed_int (unsigned char low_byte, unsigned char high_byte) |
static unsigned int | two_bytes_to_unsigned_int (unsigned char low_byte, unsigned char high_byte) |
static void | unsigned_int_to_two_bytes (int n, unsigned char *byte_ptr) |
int | vm (int t_v, int s_v, int r_v) |
static float | voltConvert (unsigned char reading, float range) |
float | voltCpuGet (void) |
float | voltMotorGet (void) |
static int | voltPackageProcess (unsigned char *inbuf, unsigned char *voltCPU, unsigned char *voltMotor) |
static int | Write_Pkg (int fd, unsigned char *outbuf) |
int | ws (unsigned char t_ws, unsigned char s_ws, unsigned char r_ws, unsigned char timeout) |
int | zr () |
Variables | |
static unsigned char | buf [BUFSIZE] |
static unsigned char * | bufe |
static unsigned char * | bufp |
int | conn_value |
int | connect_type = 1 |
char | cvsid_host_client_Ndirect_c [] = "$Header: /home/cvs/host/client/direct.c,v 1.4 1999/11/12 07:28:19 jake Exp $" |
int | DEFAULT_ROBOT_TCP_PORT = 65001 |
int | DEFAULT_SERIAL_BAUD = 38400 |
char * | device |
static int | errorp = 0 |
static int | Fd = -1 |
char | Host_name [255] = "" |
int | Laser [2 *NUM_LASER+1] |
double | LASER_CALIBRATION [8] |
static int | laser_mode = 51 |
double | LASER_OFFSET [2] = { 0, 0 } |
int | model |
static PosDataAll | posDataAll |
static unsigned long | posDataTime |
static int | Robot_id = -1 |
int | SERV_TCP_PORT = -1 |
char | SERVER_MACHINE_NAME [80] = "" |
int | Smask [NUM_MASK] |
static unsigned short | special_answer_size |
static unsigned char * | special_buffer |
long | State [NUM_STATE] |
static int | usedSmask [NUM_MASK] |
static unsigned char | voltageCPU |
static unsigned char | voltageMotor |
static int | wait_time |
#define CONNECT_TIMEOUT 10 /* 10 seconds */ |
#define DELETE_OBS 33 |
#define NORMAL_TIMEOUT 1 /* 1 second */ |
#define NUM_COMMANDS 36 |
#define PLACE_ROBOT 36 |
#define POS_BUMPER_PI | ( | x | ) | ( ( (x) & POS_BUMPER ) ? 1 : 0 ) |
#define POS_COMPASS_PI | ( | x | ) | ( ( (x) & POS_COMPASS ) ? 1 : 0 ) |
#define POS_INFRARED_PI | ( | x | ) | ( ( (x) & POS_INFRARED ) ? 1 : 0 ) |
#define RANGE_CPU_VOLTAGE 12.0 |
#define RANGE_MOTOR_VOLTAGE 12.85 |
#define SERIAL_OPEN_ERROR 1 |
#define SERIAL_PKG_ERROR 4 |
#define SERIAL_READ_ERROR 3 |
#define SERIAL_TIMEOUT_ERROR 5 |
#define SERIAL_WRITE_ERROR 2 |
#define SPECIAL_TIMEOUT 30 /* used for user define package */ |
#define USER_BUFFER_LENGTH 0xFFFF |
typedef struct _PosDataAll PosDataAll |
int add_obstacle | ( | long | obs[2 *MAX_VERTICES+1] | ) |
long arm_mv | ( | long | l_mode, |
long | l_v, | ||
long | g_mode, | ||
long | g_v | ||
) |
long arm_ws | ( | short | l, |
short | g, | ||
long | timeout, | ||
long * | time_remain | ||
) |
static unsigned char bits_to_byte | ( | char | bt0, |
char | bt1, | ||
char | bt2, | ||
char | bt3, | ||
char | bt4, | ||
char | bt5, | ||
char | bt6, | ||
char | bt7 | ||
) | [static] |
static unsigned char buf_fill | ( | int | fd, |
int | conn_type | ||
) | [static] |
static long combine_bumper_vector | ( | unsigned char | b1, |
unsigned char | b2, | ||
unsigned char | b3 | ||
) | [static] |
static int Comm_Robot | ( | int | fd, |
unsigned char | command[BUFSIZE] | ||
) | [static] |
int conf_ls | ( | unsigned int | mode, |
unsigned int | threshold, | ||
unsigned int | width, | ||
unsigned int | num_data, | ||
unsigned int | processing | ||
) |
int conf_sg | ( | unsigned int | threshold, |
unsigned int | min_points, | ||
unsigned int | gap | ||
) |
int connect_robot | ( | long | robot_id, |
... | |||
) |
static void convert_laser | ( | int * | laser | ) | [static] |
static char* convertAddr | ( | char * | name, |
char * | addr | ||
) | [static] |
int create_robot | ( | long | robot_id | ) |
int delete_Obs | ( | long | obs[2 *MAX_VERTICES+1] | ) |
int delete_obstacle | ( | long | obs[2 *MAX_VERTICES+1] | ) |
int disconnect_robot | ( | long | robot_id | ) |
int draw_arc | ( | long | x_0, |
long | y_0, | ||
long | w, | ||
long | h, | ||
int | th1, | ||
int | th2, | ||
int | mode | ||
) |
int draw_line | ( | long | x_1, |
long | y_1, | ||
long | x_2, | ||
long | y_2, | ||
int | mode | ||
) |
int draw_robot | ( | long | x, |
long | y, | ||
int | th, | ||
int | tu, | ||
int | mode | ||
) |
signed short extract2byteint | ( | unsigned char * | buffer, |
unsigned short * | index | ||
) |
unsigned short extract2byteuint | ( | unsigned char * | buffer, |
unsigned short * | index | ||
) |
signed long extract4byteint | ( | unsigned char * | buffer, |
unsigned short * | index | ||
) |
unsigned long extract4byteuint | ( | unsigned char * | buffer, |
unsigned short * | index | ||
) |
int extract_receive_buffer_header | ( | unsigned short * | length, |
unsigned char * | serial_number, | ||
unsigned char * | packet_type, | ||
unsigned char * | buffer | ||
) |
signed char extractchar | ( | unsigned char * | buffer, |
unsigned short * | index | ||
) |
double extractdouble | ( | unsigned char * | buffer, |
unsigned short * | index | ||
) |
unsigned char extractuchar | ( | unsigned char * | buffer, |
unsigned short * | index | ||
) |
int get_robot_conf | ( | long * | conf | ) |
static unsigned char GETC | ( | int | fd, |
int | conn_type | ||
) | [static] |
int init_receive_buffer | ( | unsigned short * | index | ) |
int init_send_buffer | ( | unsigned short * | index | ) |
int init_sensors | ( | void | ) |
int motion_check | ( | long | type, |
double | a1, | ||
double | a2, | ||
double | a3, | ||
double | a4, | ||
double | a5, | ||
double | a6, | ||
double | a7, | ||
double | collide[3] | ||
) |
int move_Obs | ( | long | obs[2 *MAX_VERTICES+1], |
long | dx, | ||
long | dy | ||
) |
int move_obstacle | ( | long | obs[2 *MAX_VERTICES+1], |
long | dx, | ||
long | dy | ||
) |
int mv | ( | int | t_mode, |
int | t_mv, | ||
int | s_mode, | ||
int | s_mv, | ||
int | r_mode, | ||
int | r_mv | ||
) |
int open_serial | ( | char * | port, |
unsigned short | baud | ||
) |
int pa | ( | int | t_pa, |
int | s_pa, | ||
int | r_pa | ||
) |
int place_robot | ( | int | x, |
int | y, | ||
int | th, | ||
int | tu | ||
) |
int posBumperGet | ( | PosData * | posData | ) |
int posCompassGet | ( | PosData * | posData | ) |
int posDataCheck | ( | void | ) |
int posDataRequest | ( | int | posRequest | ) |
int posInfraredGet | ( | PosData * | posData, |
int | infraredNumber | ||
) |
int posInfraredRingGet | ( | PosData | posData[INFRAREDS] | ) |
int posLaserGet | ( | PosData * | posData | ) |
static long posLongExtract | ( | unsigned char * | inbuf | ) | [static] |
static int posPackageProcess | ( | unsigned char * | inbuf, |
PosData * | posData | ||
) | [static] |
int posSonarGet | ( | PosData * | posData, |
int | sonarNumber | ||
) |
int posSonarRingGet | ( | PosData | posData[SONARS] | ) |
int posTimeGet | ( | void | ) |
static unsigned long posUnsignedLongExtract | ( | unsigned char * | inbuf | ) | [static] |
int predict_sensors | ( | int | x, |
int | y, | ||
int | th, | ||
int | tu, | ||
long * | state, | ||
int * | laser | ||
) |
static void Process_Acceleration_Pkg | ( | unsigned char | inbuf[BUFSIZE] | ) | [static] |
static void Process_Bumper_Pkg | ( | unsigned char | inbuf[BUFSIZE] | ) | [static] |
static void Process_Compass_Conf_Pkg | ( | unsigned char | inbuf[BUFSIZE] | ) | [static] |
static void Process_Compass_Pkg | ( | unsigned char | inbuf[BUFSIZE] | ) | [static] |
static void Process_Configuration_Pkg | ( | unsigned char | inbuf[BUFSIZE] | ) | [static] |
static void Process_Infrared_Pkg | ( | unsigned char | inbuf[BUFSIZE] | ) | [static] |
static void Process_Laser_Line_Pkg | ( | unsigned char | inbuf[BUFSIZE] | ) | [static] |
static void Process_Laser_Point_Pkg | ( | unsigned char | inbuf[BUFSIZE] | ) | [static] |
static int Process_Robot_Resp | ( | unsigned char | inbuf[BUFSIZE] | ) | [static] |
static void Process_Sonar_Pkg | ( | unsigned char | inbuf[BUFSIZE] | ) | [static] |
static void Process_Special_Pkg | ( | unsigned char | inbuf[BUFSIZE] | ) | [static] |
static void Process_State_Pkg | ( | unsigned char | inbuf[BUFSIZE] | ) | [static] |
static void Process_Velocity_Pkg | ( | unsigned char | inbuf[BUFSIZE] | ) | [static] |
static void ProjectPhy | ( | double | xi1, |
double | yi1, | ||
double * | x, | ||
double * | y | ||
) | [static] |
int quit_server | ( | void | ) |
static int Read_Pkg | ( | int | fd, |
int | conn_type, | ||
unsigned char * | inbuf | ||
) | [static] |
int real_robot | ( | void | ) |
static int serial_ready | ( | int | fd, |
int | wait | ||
) | [static] |
int server_is_running | ( | void | ) |
int set_serv_tcp_port | ( | int | port | ) |
int set_server_machine_name | ( | char * | sname | ) |
static void signed_int_to_two_bytes | ( | int | n, |
unsigned char * | byte_ptr | ||
) | [static] |
int simulated_robot | ( | void | ) |
int special_request | ( | unsigned char * | user_send_buffer, |
unsigned char * | user_receive_buffer | ||
) |
int stuff2byteint | ( | signed short | data, |
unsigned char * | buffer, | ||
unsigned short * | index | ||
) |
int stuff2byteuint | ( | unsigned short | data, |
unsigned char * | buffer, | ||
unsigned short * | index | ||
) |
int stuff4byteint | ( | signed long | data, |
unsigned char * | buffer, | ||
unsigned short * | index | ||
) |
int stuff4byteuint | ( | unsigned long | data, |
unsigned char * | buffer, | ||
unsigned short * | index | ||
) |
void stuff_length_type | ( | int | length, |
int | ptype, | ||
unsigned char * | byte_ptr | ||
) |
int stuff_send_buffer_header | ( | unsigned short | index, |
unsigned char | serial_number, | ||
unsigned char | packet_type, | ||
unsigned char * | buffer | ||
) |
void stuff_three_signed_int | ( | int | length, |
int | ptype, | ||
int | num1, | ||
int | num2, | ||
int | num3, | ||
unsigned char * | byte_ptr | ||
) |
void stuff_three_unsigned_int | ( | int | length, |
int | ptype, | ||
int | num1, | ||
int | num2, | ||
int | num3, | ||
unsigned char * | byte_ptr | ||
) |
void stuff_two_signed_int | ( | int | length, |
int | ptype, | ||
int | num1, | ||
int | num2, | ||
unsigned char * | byte_ptr | ||
) |
int stuffchar | ( | signed char | data, |
unsigned char * | buffer, | ||
unsigned short * | index | ||
) |
int stuffdouble | ( | double | data, |
unsigned char * | buffer, | ||
unsigned short * | index | ||
) |
int stuffuchar | ( | unsigned char | data, |
unsigned char * | buffer, | ||
unsigned short * | index | ||
) |
static int timePackageProcess | ( | unsigned char * | inbuf, |
unsigned long * | timeS | ||
) | [static] |
static int two_bytes_to_signed_int | ( | unsigned char | low_byte, |
unsigned char | high_byte | ||
) | [static] |
static unsigned int two_bytes_to_unsigned_int | ( | unsigned char | low_byte, |
unsigned char | high_byte | ||
) | [static] |
static void unsigned_int_to_two_bytes | ( | int | n, |
unsigned char * | byte_ptr | ||
) | [static] |
static float voltConvert | ( | unsigned char | reading, |
float | range | ||
) | [static] |
float voltCpuGet | ( | void | ) |
float voltMotorGet | ( | void | ) |
static int voltPackageProcess | ( | unsigned char * | inbuf, |
unsigned char * | voltCPU, | ||
unsigned char * | voltMotor | ||
) | [static] |
static int Write_Pkg | ( | int | fd, |
unsigned char * | outbuf | ||
) | [static] |
int ws | ( | unsigned char | t_ws, |
unsigned char | s_ws, | ||
unsigned char | r_ws, | ||
unsigned char | timeout | ||
) |
int conn_value |
int connect_type = 1 |
char cvsid_host_client_Ndirect_c[] = "$Header: /home/cvs/host/client/direct.c,v 1.4 1999/11/12 07:28:19 jake Exp $" |
int DEFAULT_ROBOT_TCP_PORT = 65001 |
int DEFAULT_SERIAL_BAUD = 38400 |
double LASER_CALIBRATION[8] |
int laser_mode = 51 [static] |
double LASER_OFFSET[2] = { 0, 0 } |
PosDataAll posDataAll [static] |
unsigned long posDataTime [static] |
int SERV_TCP_PORT = -1 |
char SERVER_MACHINE_NAME[80] = "" |
unsigned short special_answer_size [static] |
unsigned char* special_buffer [static] |
unsigned char voltageCPU [static] |
unsigned char voltageMotor [static] |