#include <unistd.h>
#include <stdlib.h>
#include <stdio.h>
#include <math.h>
#include <memory.h>
#include <errno.h>
#include <sys/types.h>
#include <sys/time.h>
#include <sys/socket.h>
#include <netinet/in.h>
#include <arpa/inet.h>
#include <netdb.h>
#include <fcntl.h>
#include <signal.h>
#include "Nclient.h"
Go to the source code of this file.
Classes | |
struct | _PosDataAll |
Defines | |
#define | AC_MSG 10 |
#define | ACCELERATION_MSG 90 |
#define | ADDOBS_MSG 50 |
#define | BUMPER_MSG 87 |
#define | COMPASS_MSG 86 |
#define | CONF_CP_MSG 24 |
#define | CONF_IR_MSG 22 |
#define | CONF_LS_MSG 25 |
#define | CONF_SG_MSG 36 |
#define | CONF_SN_MSG 23 |
#define | CONF_TM_MSG 26 |
#define | CONFIGURATION_MSG 88 |
#define | CONNECT_ROBOT_MSG 102 |
#define | CREATE_ROBOT_MSG 101 |
#define | CT_MSG 16 |
#define | DA_MSG 38 |
#define | DEBUG |
#define | DELETEOBS_MSG 51 |
#define | DISCONNECT_MSG 103 |
#define | DP_MSG 21 |
#define | DRAWARC_MSG 62 |
#define | DRAWLINE_MSG 61 |
#define | DRAWROBOT_MSG 60 |
#define | ERROR_MSG 91 |
#define | FALSE 0 |
#define | GET_BP_MSG 35 |
#define | GET_CONF_MSG 200 |
#define | GET_CP_MSG 32 |
#define | GET_IR_MSG 27 |
#define | GET_LS_MSG 33 |
#define | GET_RA_MSG 31 |
#define | GET_RC_MSG 29 |
#define | GET_RPX_MSG 75 |
#define | GET_RV_MSG 30 |
#define | GET_SG_MSG 37 |
#define | GET_SN_MSG 28 |
#define | GS_MSG 15 |
#define | INFRARED_MSG 83 |
#define | INTERSECT_MSG 401 |
#define | IPC_ERROR 111 |
#define | IS_SERVER_ALIVE_ACK 1 |
#define | IS_SERVER_ALIVE_MSG 0 /* message types */ |
#define | LASER_MSG 85 |
#define | LP_MSG 18 |
#define | MAX_HOST_NAME_LENGTH 100 |
#define | MAX_MESSAGE 100 |
#define | MAX_MESSAGE 100 |
#define | MAX_MESSAGE 100 |
#define | MAX_USER_BUF 0xFFFF |
#define | MAX_VERT 10 |
#define | MAX_VERTICES 10 /* maximum number of verices in a poly */ |
#define | MAX_VERTICES 10 |
#define | MCHECK_MSG 400 |
#define | MOVED_MSG 81 |
#define | MOVEOBS_MSG 52 |
#define | MV_MSG 43 |
#define | NEW_SOCKET 2 |
#define | NEWWORLD_MSG 53 |
#define | NUM_LASER 482 |
#define | NUM_LASER 482 |
#define | NUM_MASK 44 |
#define | NUM_MASK 44 |
#define | NUM_STATE 45 |
#define | NUM_STATE 45 |
#define | PA_MSG 14 |
#define | PR_MSG 13 |
#define | PREDICTSENSOR_MSG 42 |
#define | QUIT_MSG 70 |
#define | RANGE_CPU_VOLTAGE 12.0 |
#define | RANGE_MOTOR_VOLTAGE 12.85 |
#define | REALROBOT_MSG 71 |
#define | RECEIVE_MESSAGE_MSG 73 |
#define | REFRESHACTTRACE_MSG 152 |
#define | REFRESHALL_MSG 150 |
#define | REFRESHALLSENSORS_MSG 154 |
#define | REFRESHALLTRACES_MSG 151 |
#define | REFRESHBPSENSOR_MSG 155 |
#define | REFRESHENCTRACE_MSG 153 |
#define | REFRESHGRAPHICS_MSG 159 |
#define | REFRESHIRSENSOR_MSG 156 |
#define | REFRESHLSSENSOR_MSG 158 |
#define | REFRESHSNSENSOR_MSG 157 |
#define | REPLY_MSG 82 |
#define | RMOVE_MSG 40 |
#define | RPLACE_MSG 41 |
#define | RPX_MSG 76 |
#define | SEND_MESSAGE_MSG 72 |
#define | SERIAL_ERROR 11 |
#define | SETUP_LS_MSG 34 |
#define | SIMULATEDROBOT_MSG 74 |
#define | SONAR_MSG 84 |
#define | SP_MSG 11 |
#define | SPECIAL_MSG 300 |
#define | ST_MSG 17 |
#define | STATE_MSG 80 |
#define | TK_MSG 19 |
#define | TRUE 1 |
#define | VELOCITY_MSG 89 |
#define | VM_MSG 12 |
#define | WS_MSG 39 |
#define | ZR_MSG 20 |
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) |
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_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,...) |
char * | convertAddr (char *name, char *addr) |
int | create_robot (long robot_id) |
int | ct (void) |
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 (void) |
int | get_cp (void) |
int | get_ir (void) |
int | get_laser (int laser[2 *NUM_LASER+1]) |
int | get_ls (void) |
int | get_mask (int mask[NUM_MASK]) |
int | get_ra (void) |
int | get_rc (void) |
int | get_robot_conf (long *conf) |
int | get_rpx (long *robot_pos) |
int | get_rv (void) |
int | get_sg (void) |
int | get_sn (void) |
int | get_state (long state[NUM_STATE]) |
int | gethostname (char *name, int len) |
int | gs (void) |
void | init_mask (void) |
int | init_receive_buffer (unsigned short *index) |
int | init_send_buffer (unsigned short *index) |
int | init_sensors (void) |
static int | ipc_comm (struct request_struct *this_request, struct reply_struct *this_reply) |
int | lp (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 | new_world (void) |
static int | open_socket_to_send_data (int tcp_port_num) |
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) |
static int | posDataProcess (long *buffer, int current, PosData *posData) |
int | posDataRequest (int posRequest) |
int | posInfraredGet (PosData *posData, int infraredNumber) |
int | posInfraredRingGet (PosData posData[INFRAREDS]) |
int | posLaserGet (PosData *posData) |
int | posSonarGet (PosData *posData, int sonarNumber) |
int | posSonarRingGet (PosData posData[SONARS]) |
int | posTimeGet (void) |
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 int | process_bumper_reply (struct reply_struct *this_reply) |
static int | process_compass_reply (struct reply_struct *this_reply) |
static int | process_conf_reply (struct reply_struct *this_reply, long *conf) |
static int | process_configuration_reply (struct reply_struct *this_reply) |
static int | process_infrared_reply (struct reply_struct *this_reply) |
static int | process_laser_reply (struct reply_struct *this_reply) |
static int | process_mcheck_reply (struct reply_struct *this_reply, double collide[3]) |
static int | process_obstacle_reply (struct reply_struct *this_reply, long *obs) |
static int | process_predict_reply (struct reply_struct *this_reply, long *state, int *laser) |
static int | process_rpx_reply (struct reply_struct *this_reply, long *robot_pos) |
static int | process_simple_reply (struct reply_struct *this_reply) |
static int | process_socket_reply (struct reply_struct *this_reply) |
static int | process_sonar_reply (struct reply_struct *this_reply) |
static int | process_special_reply (struct reply_struct *this_reply, unsigned char *data) |
static int | process_state_reply (struct reply_struct *this_reply) |
static int | process_velocity_reply (struct reply_struct *this_reply) |
int | quit_server (void) |
static int | read_reply_from_socket (int sock, struct reply_struct *this_reply) |
static int | readn (register int fd, register char *ptr, register int nbytes) |
int | real_robot (void) |
int | refresh_actual_trace (void) |
int | refresh_all (void) |
int | refresh_all_sensors (void) |
int | refresh_all_traces (void) |
int | refresh_bumper_sensor (void) |
int | refresh_client_graphics (void) |
int | refresh_encoder_trace (void) |
int | refresh_infrared_sensor (void) |
int | refresh_laser_sensor (void) |
int | refresh_sonar_sensor (void) |
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) |
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 (void) |
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) |
int | stuff_send_buffer_header (unsigned short index, unsigned char serial_number, unsigned char packet_type, unsigned char *buffer) |
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 | timeDataProcess (long *buffer, int current, TimeData *theTime) |
int | tk (char *talk_string) |
int | vm (int t_vm, int s_vm, int r_vm) |
static float | voltConvert (unsigned char reading, float range) |
float | voltCpuGet (void) |
static int | voltDataProcess (long *buffer, int current, unsigned char *voltCPU, unsigned char *voltMotor) |
float | voltMotorGet (void) |
static int | write_request_to_socket (int sock, struct request_struct *this_request) |
static int | writen (register int fd, register char *ptr, register int nbytes) |
int | ws (unsigned char t_ws, unsigned char s_ws, unsigned char r_ws, unsigned char timeout) |
int | zr (void) |
Variables | |
int | CONN_TYPE = -1 |
static int | connectedp = 0 |
char | cvsid_host_client_Nclient_c [] = "$Header: /home/cvs/host/client/Nclient.c,v 1.31 1999/07/30 22:25:29 rak Exp $" |
static int | dest_socket = 0 |
static char | Host_name [255] = "" |
int | Laser [2 *NUM_LASER+1] |
double | LASER_CALIBRATION [8] |
static int | laser_mode = 51 |
double | LASER_OFFSET [2] |
static int | own_tcp_port = 0 |
static PosDataAll | posDataAll |
static unsigned long | posDataTime |
char | ROBOT_MACHINE_NAME [80] = "" |
int | ROBOT_TCP_PORT = -1 |
int | SERIAL_BAUD = -1 |
char | SERIAL_PORT [40] = "" |
int | SERV_TCP_PORT = 7019 |
char | SERVER_MACHINE_NAME [80] = "" |
int | Smask [NUM_MASK] |
long | State [NUM_STATE] |
static struct reply_struct | the_reply |
static struct request_struct | the_request |
static int | usedSmask [NUM_MASK] |
static unsigned char | voltageCPU |
static unsigned char | voltageMotor |
#define ACCELERATION_MSG 90 |
#define ADDOBS_MSG 50 |
#define BUMPER_MSG 87 |
#define COMPASS_MSG 86 |
#define CONF_CP_MSG 24 |
#define CONF_IR_MSG 22 |
#define CONF_LS_MSG 25 |
#define CONF_SG_MSG 36 |
#define CONF_SN_MSG 23 |
#define CONF_TM_MSG 26 |
#define CONFIGURATION_MSG 88 |
#define CONNECT_ROBOT_MSG 102 |
#define CREATE_ROBOT_MSG 101 |
#define DELETEOBS_MSG 51 |
#define DISCONNECT_MSG 103 |
#define DRAWARC_MSG 62 |
#define DRAWLINE_MSG 61 |
#define DRAWROBOT_MSG 60 |
#define GET_BP_MSG 35 |
#define GET_CONF_MSG 200 |
#define GET_CP_MSG 32 |
#define GET_IR_MSG 27 |
#define GET_LS_MSG 33 |
#define GET_RA_MSG 31 |
#define GET_RC_MSG 29 |
#define GET_RPX_MSG 75 |
#define GET_RV_MSG 30 |
#define GET_SG_MSG 37 |
#define GET_SN_MSG 28 |
#define INFRARED_MSG 83 |
#define INTERSECT_MSG 401 |
#define IS_SERVER_ALIVE_ACK 1 |
#define IS_SERVER_ALIVE_MSG 0 /* message types */ |
#define MAX_HOST_NAME_LENGTH 100 |
#define MAX_MESSAGE 100 |
#define MAX_MESSAGE 100 |
#define MAX_MESSAGE 100 |
#define MAX_USER_BUF 0xFFFF |
#define MAX_VERTICES 10 /* maximum number of verices in a poly */ |
#define MAX_VERTICES 10 |
#define MCHECK_MSG 400 |
#define MOVEOBS_MSG 52 |
#define NEW_SOCKET 2 |
#define NEWWORLD_MSG 53 |
#define PREDICTSENSOR_MSG 42 |
#define RANGE_CPU_VOLTAGE 12.0 |
#define RANGE_MOTOR_VOLTAGE 12.85 |
#define REALROBOT_MSG 71 |
#define RECEIVE_MESSAGE_MSG 73 |
#define REFRESHACTTRACE_MSG 152 |
#define REFRESHALL_MSG 150 |
#define REFRESHALLSENSORS_MSG 154 |
#define REFRESHALLTRACES_MSG 151 |
#define REFRESHBPSENSOR_MSG 155 |
#define REFRESHENCTRACE_MSG 153 |
#define REFRESHGRAPHICS_MSG 159 |
#define REFRESHIRSENSOR_MSG 156 |
#define REFRESHLSSENSOR_MSG 158 |
#define REFRESHSNSENSOR_MSG 157 |
#define RPLACE_MSG 41 |
#define SEND_MESSAGE_MSG 72 |
#define SERIAL_ERROR 11 |
#define SETUP_LS_MSG 34 |
#define SIMULATEDROBOT_MSG 74 |
#define SPECIAL_MSG 300 |
#define VELOCITY_MSG 89 |
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] |
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, |
... | |||
) |
char * convertAddr | ( | char * | name, |
char * | addr | ||
) |
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 | ) |
int gethostname | ( | char * | name, |
int | len | ||
) |
int init_receive_buffer | ( | unsigned short * | index | ) |
int init_send_buffer | ( | unsigned short * | index | ) |
int init_sensors | ( | void | ) |
static int ipc_comm | ( | struct request_struct * | this_request, |
struct reply_struct * | this_reply | ||
) | [static] |
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 | ||
) |
static int open_socket_to_send_data | ( | int | tcp_port_num | ) | [static] |
int place_robot | ( | int | x, |
int | y, | ||
int | th, | ||
int | tu | ||
) |
int posBumperGet | ( | PosData * | posData | ) |
int posCompassGet | ( | PosData * | posData | ) |
int posDataCheck | ( | void | ) |
static int posDataProcess | ( | long * | buffer, |
int | current, | ||
PosData * | posData | ||
) | [static] |
int posDataRequest | ( | int | posRequest | ) |
int posInfraredGet | ( | PosData * | posData, |
int | infraredNumber | ||
) |
int posInfraredRingGet | ( | PosData | posData[INFRAREDS] | ) |
int posLaserGet | ( | PosData * | posData | ) |
int posSonarGet | ( | PosData * | posData, |
int | sonarNumber | ||
) |
int posSonarRingGet | ( | PosData | posData[SONARS] | ) |
int posTimeGet | ( | void | ) |
int predict_sensors | ( | int | x, |
int | y, | ||
int | th, | ||
int | tu, | ||
long * | state, | ||
int * | laser | ||
) |
static int process_bumper_reply | ( | struct reply_struct * | this_reply | ) | [static] |
static int process_compass_reply | ( | struct reply_struct * | this_reply | ) | [static] |
static int process_conf_reply | ( | struct reply_struct * | this_reply, |
long * | conf | ||
) | [static] |
static int process_configuration_reply | ( | struct reply_struct * | this_reply | ) | [static] |
static int process_infrared_reply | ( | struct reply_struct * | this_reply | ) | [static] |
static int process_laser_reply | ( | struct reply_struct * | this_reply | ) | [static] |
static int process_mcheck_reply | ( | struct reply_struct * | this_reply, |
double | collide[3] | ||
) | [static] |
static int process_obstacle_reply | ( | struct reply_struct * | this_reply, |
long * | obs | ||
) | [static] |
static int process_predict_reply | ( | struct reply_struct * | this_reply, |
long * | state, | ||
int * | laser | ||
) | [static] |
static int process_rpx_reply | ( | struct reply_struct * | this_reply, |
long * | robot_pos | ||
) | [static] |
static int process_simple_reply | ( | struct reply_struct * | this_reply | ) | [static] |
static int process_socket_reply | ( | struct reply_struct * | this_reply | ) | [static] |
static int process_sonar_reply | ( | struct reply_struct * | this_reply | ) | [static] |
static int process_special_reply | ( | struct reply_struct * | this_reply, |
unsigned char * | data | ||
) | [static] |
static int process_state_reply | ( | struct reply_struct * | this_reply | ) | [static] |
static int process_velocity_reply | ( | struct reply_struct * | this_reply | ) | [static] |
int quit_server | ( | void | ) |
static int read_reply_from_socket | ( | int | sock, |
struct reply_struct * | this_reply | ||
) | [static] |
static int readn | ( | register int | fd, |
register char * | ptr, | ||
register int | nbytes | ||
) | [static] |
int real_robot | ( | void | ) |
int refresh_actual_trace | ( | void | ) |
int refresh_all | ( | void | ) |
int refresh_all_sensors | ( | void | ) |
int refresh_all_traces | ( | void | ) |
int refresh_bumper_sensor | ( | void | ) |
int refresh_client_graphics | ( | void | ) |
int refresh_encoder_trace | ( | void | ) |
int refresh_infrared_sensor | ( | void | ) |
int refresh_laser_sensor | ( | void | ) |
int refresh_sonar_sensor | ( | void | ) |
int server_is_running | ( | void | ) |
int set_serv_tcp_port | ( | int | port | ) |
int set_server_machine_name | ( | char * | sname | ) |
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 | ||
) |
int stuff_send_buffer_header | ( | unsigned short | index, |
unsigned char | serial_number, | ||
unsigned char | packet_type, | ||
unsigned char * | buffer | ||
) |
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 timeDataProcess | ( | long * | buffer, |
int | current, | ||
TimeData * | theTime | ||
) | [static] |
static float voltConvert | ( | unsigned char | reading, |
float | range | ||
) | [static] |
float voltCpuGet | ( | void | ) |
static int voltDataProcess | ( | long * | buffer, |
int | current, | ||
unsigned char * | voltCPU, | ||
unsigned char * | voltMotor | ||
) | [static] |
float voltMotorGet | ( | void | ) |
static int write_request_to_socket | ( | int | sock, |
struct request_struct * | this_request | ||
) | [static] |
static int writen | ( | register int | fd, |
register char * | ptr, | ||
register int | nbytes | ||
) | [static] |
int ws | ( | unsigned char | t_ws, |
unsigned char | s_ws, | ||
unsigned char | r_ws, | ||
unsigned char | timeout | ||
) |
int connectedp = 0 [static] |
char cvsid_host_client_Nclient_c[] = "$Header: /home/cvs/host/client/Nclient.c,v 1.31 1999/07/30 22:25:29 rak Exp $" |
int dest_socket = 0 [static] |
double LASER_CALIBRATION[8] |
int laser_mode = 51 [static] |
double LASER_OFFSET[2] |
int own_tcp_port = 0 [static] |
PosDataAll posDataAll [static] |
unsigned long posDataTime [static] |
char ROBOT_MACHINE_NAME[80] = "" |
int ROBOT_TCP_PORT = -1 |
int SERIAL_BAUD = -1 |
char SERIAL_PORT[40] = "" |
int SERV_TCP_PORT = 7019 |
char SERVER_MACHINE_NAME[80] = "" |
struct reply_struct the_reply [static] |
struct request_struct the_request [static] |
unsigned char voltageCPU [static] |
unsigned char voltageMotor [static] |