00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027 #ifndef PLAYER_H
00028 #define PLAYER_H
00029
00030
00031
00032 #include "playerconfig.h"
00033
00034
00035
00036
00037
00038 #define PLAYER_STXX ((uint16_t) 0x5878)
00039
00040
00041 #define PLAYER_TRANSPORT_TCP 1
00042 #define PLAYER_TRANSPORT_UDP 2
00043
00044
00045 #define PLAYER_MSGTYPE_DATA ((uint16_t)1)
00046 #define PLAYER_MSGTYPE_CMD ((uint16_t)2)
00047 #define PLAYER_MSGTYPE_REQ ((uint16_t)3)
00048 #define PLAYER_MSGTYPE_RESP_ACK ((uint16_t)4)
00049 #define PLAYER_MSGTYPE_SYNCH ((uint16_t)5)
00050 #define PLAYER_MSGTYPE_RESP_NACK ((uint16_t)6)
00051 #define PLAYER_MSGTYPE_RESP_ERR ((uint16_t)7)
00052
00053
00054
00055 #define PLAYER_MAX_DEVICE_STRING_LEN 64
00056
00057
00058 #define PLAYER_NULL_CODE ((uint16_t)256) // /dev/null analogue
00059 #define PLAYER_PLAYER_CODE ((uint16_t)1) // the server itself
00060 #define PLAYER_POWER_CODE ((uint16_t)2) // power subsystem
00061 #define PLAYER_GRIPPER_CODE ((uint16_t)3) // gripper
00062 #define PLAYER_POSITION_CODE ((uint16_t)4) // device that moves about
00063 #define PLAYER_SONAR_CODE ((uint16_t)5) // fixed range-finder
00064 #define PLAYER_LASER_CODE ((uint16_t)6) // scanning range-finder
00065 #define PLAYER_BLOBFINDER_CODE ((uint16_t)7) // visual blobfinder
00066 #define PLAYER_PTZ_CODE ((uint16_t)8) // pan-tilt-zoom unit
00067 #define PLAYER_AUDIO_CODE ((uint16_t)9) // audio I/O
00068 #define PLAYER_FIDUCIAL_CODE ((uint16_t)10) // fiducial detector
00069 #define PLAYER_SPEECH_CODE ((uint16_t)12) // speech I/O
00070 #define PLAYER_GPS_CODE ((uint16_t)13) // GPS unit
00071 #define PLAYER_BUMPER_CODE ((uint16_t)14) // bumper array
00072 #define PLAYER_TRUTH_CODE ((uint16_t)15) // ground-truth (via Stage)
00073 #define PLAYER_IDARTURRET_CODE ((uint16_t)16) // ranging + comms
00074 #define PLAYER_IDAR_CODE ((uint16_t)17) // ranging + comms
00075 #define PLAYER_DESCARTES_CODE ((uint16_t)18) // the Descartes platform
00076 #define PLAYER_DIO_CODE ((uint16_t)20) // digital I/O
00077 #define PLAYER_AIO_CODE ((uint16_t)21) // analog I/O
00078 #define PLAYER_IR_CODE ((uint16_t)22) // IR array
00079 #define PLAYER_WIFI_CODE ((uint16_t)23) // wifi card status
00080 #define PLAYER_WAVEFORM_CODE ((uint16_t)24) // fetch raw waveforms
00081 #define PLAYER_LOCALIZE_CODE ((uint16_t)25) // localization
00082 #define PLAYER_MCOM_CODE ((uint16_t)26) // multicoms
00083 #define PLAYER_SOUND_CODE ((uint16_t)27) // sound file playback
00084 #define PLAYER_AUDIODSP_CODE ((uint16_t)28) // audio dsp I/O
00085 #define PLAYER_AUDIOMIXER_CODE ((uint16_t)29) // audio I/O
00086 #define PLAYER_POSITION3D_CODE ((uint16_t)30) // 3-D position
00087 #define PLAYER_SIMULATION_CODE ((uint16_t)31) // simulators
00088 #define PLAYER_SERVICE_ADV_CODE ((uint16_t)32) // LAN service advertisement
00089 #define PLAYER_BLINKENLIGHT_CODE ((uint16_t)33) // blinking lights
00090 #define PLAYER_NOMAD_CODE ((uint16_t)34) // Nomad robot
00091 #define PLAYER_CAMERA_CODE ((uint16_t)40) // camera device (gazebo)
00092 #define PLAYER_MAP_CODE ((uint16_t)42) // get a map
00093 #define PLAYER_PLANNER_CODE ((uint16_t)44) // 2D motion planner
00094 #define PLAYER_LOG_CODE ((uint16_t)45) // log read/write control
00095 #define PLAYER_ENERGY_CODE ((uint16_t)46) // energy consumption & charging
00096 #define PLAYER_MOTOR_CODE ((uint16_t)47) // motor interface
00097 #define PLAYER_POSITION2D_CODE ((uint16_t)48) // 2-D position
00098 #define PLAYER_JOYSTICK_CODE ((uint16_t)49) // Joytstick
00099 #define PLAYER_SPEECH_RECOGNITION_CODE ((uint16_t)50) // speech recognitionI/O
00100 #define PLAYER_OPAQUE_CODE ((uint16_t)51) // plugin interface
00101
00102
00103 #define PLAYER_NULL_STRING "null"
00104 #define PLAYER_PLAYER_STRING "player"
00105 #define PLAYER_POWER_STRING "power"
00106 #define PLAYER_GRIPPER_STRING "gripper"
00107 #define PLAYER_POSITION_STRING "position"
00108 #define PLAYER_SONAR_STRING "sonar"
00109 #define PLAYER_LASER_STRING "laser"
00110 #define PLAYER_BLOBFINDER_STRING "blobfinder"
00111 #define PLAYER_PTZ_STRING "ptz"
00112 #define PLAYER_AUDIO_STRING "audio"
00113 #define PLAYER_FIDUCIAL_STRING "fiducial"
00114 #define PLAYER_SPEECH_STRING "speech"
00115 #define PLAYER_SPEECH_RECOGNITION_STRING "speech_recognition"
00116 #define PLAYER_GPS_STRING "gps"
00117 #define PLAYER_BUMPER_STRING "bumper"
00118 #define PLAYER_TRUTH_STRING "truth"
00119 #define PLAYER_IDARTURRET_STRING "idarturret"
00120 #define PLAYER_IDAR_STRING "idar"
00121 #define PLAYER_DESCARTES_STRING "descartes"
00122 #define PLAYER_DIO_STRING "dio"
00123 #define PLAYER_AIO_STRING "aio"
00124 #define PLAYER_IR_STRING "ir"
00125 #define PLAYER_WIFI_STRING "wifi"
00126 #define PLAYER_WAVEFORM_STRING "waveform"
00127 #define PLAYER_LOCALIZE_STRING "localize"
00128 #define PLAYER_MCOM_STRING "mcom"
00129 #define PLAYER_SOUND_STRING "sound"
00130 #define PLAYER_AUDIODSP_STRING "audiodsp"
00131 #define PLAYER_AUDIOMIXER_STRING "audiomixer"
00132 #define PLAYER_MOTOR_STRING "motor"
00133 #define PLAYER_POSITION2D_STRING "position2d"
00134 #define PLAYER_POSITION3D_STRING "position3d"
00135 #define PLAYER_SERVICE_ADV_STRING "service_adv"
00136 #define PLAYER_SIMULATION_STRING "simulation"
00137 #define PLAYER_BLINKENLIGHT_STRING "blinkenlight"
00138 #define PLAYER_NOMAD_STRING "nomad"
00139 #define PLAYER_ENERGY_STRING "energy"
00140 #define PLAYER_MAP_STRING "map"
00141 #define PLAYER_PLANNER_STRING "planner"
00142 #define PLAYER_LOG_STRING "log"
00143 #define PLAYER_CAMERA_STRING "camera"
00144 #define PLAYER_JOYSTICK_STRING "joystick"
00145 #define PLAYER_OPAQUE_STRING "opaque"
00146
00147
00148 #define PLAYER_MAX_DEVICES 256
00149
00150
00151
00152
00153
00154 #define PLAYER_MAX_REQREP_SIZE 4096
00155
00156
00157 #define PLAYER_PORTNUM 6665
00158
00159
00160
00161
00162 #define PLAYER_IDENT_STRING "Player v."
00163 #define PLAYER_IDENT_STRLEN 32
00164
00165 #define PLAYER_KEYLEN 32
00166
00167
00168
00169
00170 #ifndef __PACKED__
00171 #define __PACKED__ __attribute__ ((packed))
00172 #endif
00173
00174
00176 typedef struct player_msghdr
00177 {
00179 uint16_t stx;
00181 uint16_t type;
00183 uint16_t device;
00185 uint16_t device_index;
00187 uint32_t time_sec;
00189 uint32_t time_usec;
00191 uint32_t timestamp_sec;
00193 uint32_t timestamp_usec;
00195 uint32_t reserved;
00197 uint32_t size;
00198 } __PACKED__ player_msghdr_t;
00199
00200 #define PLAYER_MAX_PAYLOAD_SIZE (PLAYER_MAX_MESSAGE_SIZE - sizeof(player_msghdr_t))
00201
00214
00215 #define PLAYER_READ_MODE 114 // 'r'
00216 #define PLAYER_WRITE_MODE 119 // 'w'
00217 #define PLAYER_ALL_MODE 97 // 'a'
00218 #define PLAYER_CLOSE_MODE 99 // 'c'
00219 #define PLAYER_ERROR_MODE 101 // 'e'
00220
00225 #define PLAYER_DATAMODE_PUSH_ALL 0
00226
00230 #define PLAYER_DATAMODE_PULL_ALL 1
00231
00236 #define PLAYER_DATAMODE_PUSH_NEW 2
00237
00242 #define PLAYER_DATAMODE_PULL_NEW 3
00243
00250 #define PLAYER_DATAMODE_PUSH_ASYNC 4
00251
00252
00253 #define PLAYER_PLAYER_DEVLIST_REQ ((uint16_t)1)
00254 #define PLAYER_PLAYER_DRIVERINFO_REQ ((uint16_t)2)
00255 #define PLAYER_PLAYER_DEV_REQ ((uint16_t)3)
00256 #define PLAYER_PLAYER_DATA_REQ ((uint16_t)4)
00257 #define PLAYER_PLAYER_DATAMODE_REQ ((uint16_t)5)
00258 #define PLAYER_PLAYER_DATAFREQ_REQ ((uint16_t)6)
00259 #define PLAYER_PLAYER_AUTH_REQ ((uint16_t)7)
00260 #define PLAYER_PLAYER_NAMESERVICE_REQ ((uint16_t)8)
00261
00266 typedef struct player_device_id
00267 {
00269 uint16_t code;
00271 uint16_t index;
00273 uint16_t port;
00274 } __PACKED__ player_device_id_t;
00275
00276
00285 typedef struct player_device_devlist
00286 {
00288 uint16_t subtype;
00289
00291 uint16_t device_count;
00292
00294 player_device_id_t devices[PLAYER_MAX_DEVICES];
00295
00296 } __PACKED__ player_device_devlist_t;
00297
00302 typedef struct player_device_driverinfo
00303 {
00305 uint16_t subtype;
00306
00308 player_device_id_t id;
00309
00311 char driver_name[PLAYER_MAX_DEVICE_STRING_LEN];
00312
00313 } __PACKED__ player_device_driverinfo_t;
00314
00342 typedef struct player_device_req
00343 {
00345 uint16_t subtype;
00347 uint16_t code;
00349 uint16_t index;
00351 uint8_t access;
00352
00353 } __PACKED__ player_device_req_t;
00354
00357 typedef struct player_device_resp
00358 {
00360 uint16_t subtype;
00362 uint16_t code;
00364 uint16_t index;
00366 uint8_t access;
00368 uint8_t driver_name[PLAYER_MAX_DEVICE_STRING_LEN];
00369 } __PACKED__ player_device_resp_t;
00370
00371
00380 typedef struct player_device_data_req
00381 {
00383 uint16_t subtype;
00384 } __PACKED__ player_device_data_req_t;
00385
00393 typedef struct player_device_datamode_req
00394 {
00396 uint16_t subtype;
00398 uint8_t mode;
00399
00400 } __PACKED__ player_device_datamode_req_t;
00401
00402
00410 typedef struct player_device_datafreq_req
00411 {
00413 uint16_t subtype;
00415 uint16_t frequency;
00416 } __PACKED__ player_device_datafreq_req_t;
00417
00418
00448 typedef struct player_device_auth_req
00449 {
00451 uint16_t subtype;
00453 uint8_t auth_key[PLAYER_KEYLEN];
00454
00455 } __PACKED__ player_device_auth_req_t;
00456
00457
00459 typedef struct player_device_nameservice_req
00460 {
00462 uint16_t subtype;
00464 uint8_t name[PLAYER_MAX_DEVICE_STRING_LEN];
00466 uint16_t port;
00467 } __PACKED__ player_device_nameservice_req_t;
00468
00484 typedef struct player_power_data
00485 {
00487 uint16_t charge;
00488 } __PACKED__ player_power_data_t;
00489
00490
00531 typedef struct player_gripper_data
00532 {
00534 uint8_t state, beams;
00535 } __PACKED__ player_gripper_data_t;
00536
00537
00545 typedef struct player_gripper_cmd
00546 {
00548 uint8_t cmd, arg;
00549 } __PACKED__ player_gripper_cmd_t;
00561
00562
00563 #define PLAYER_MOTOR_POWER_REQ ((uint8_t)2)
00564 #define PLAYER_MOTOR_VELOCITY_MODE_REQ ((uint8_t)3)
00565 #define PLAYER_MOTOR_RESET_ODOM_REQ ((uint8_t)4)
00566 #define PLAYER_MOTOR_POSITION_MODE_REQ ((uint8_t)5)
00567 #define PLAYER_MOTOR_SPEED_PID_REQ ((uint8_t)6)
00568 #define PLAYER_MOTOR_POSITION_PID_REQ ((uint8_t)7)
00569 #define PLAYER_MOTOR_SPEED_PROF_REQ ((uint8_t)8)
00570 #define PLAYER_MOTOR_SET_ODOM_REQ ((uint8_t)9)
00571 #define PLAYER_MOTOR_SET_GEAR_REDUCITION_REQ ((uint8_t)10)
00572 #define PLAYER_MOTOR_SET_TICS_REQ ((uint8_t)11)
00573
00578 typedef struct player_motor_data
00579 {
00581 int32_t theta;
00583 int32_t thetaspeed;
00585 uint8_t stall;
00586 } __PACKED__ player_motor_data_t;
00587
00593 typedef struct player_motor_cmd
00594 {
00596 int32_t theta;
00598 int32_t thetaspeed;
00600 uint8_t state;
00602 uint8_t type;
00603 } __PACKED__ player_motor_cmd_t;
00604
00606 typedef struct player_motor_position_mode_req
00607 {
00609 uint8_t subtype;
00611 uint8_t state;
00612 } __PACKED__ player_motor_position_mode_req_t;
00613
00614
00622 typedef struct player_motor_velocitymode_config
00623 {
00625 uint8_t request;
00627 uint8_t value;
00628 } __PACKED__ player_motor_velocitymode_config_t;
00629
00634 typedef struct player_motor_resetodom_config
00635 {
00637 uint8_t request;
00638 } __PACKED__ player_motor_resetodom_config_t;
00639
00643 typedef struct player_motor_set_odom_req
00644 {
00646 uint8_t subtype;
00648 int32_t theta;
00649 }__PACKED__ player_motor_set_odom_req_t;
00650
00652 typedef struct player_motor_speed_pid_req
00653 {
00655 uint8_t subtype;
00657 int32_t kp, ki, kd;
00658 } __PACKED__ player_motor_speed_pid_req_t;
00659
00661 typedef struct player_motor_position_pid_req
00662 {
00664 uint8_t subtype;
00666 int32_t kp, ki, kd;
00667 } __PACKED__ player_motor_position_pid_req_t;
00668
00673 typedef struct player_motor_speed_prof_req
00674 {
00676 uint8_t subtype;
00678 int32_t speed;
00680 int32_t acc;
00681 } __PACKED__ player_motor_speed_prof_req_t;
00682
00693 typedef struct player_motor_power_config
00694 {
00696 uint8_t request;
00698 uint8_t value;
00699 } __PACKED__ player_motor_power_config_t;
00700
00705
00714
00715 #define PLAYER_POSITION_GET_GEOM_REQ ((uint8_t)1)
00716 #define PLAYER_POSITION_MOTOR_POWER_REQ ((uint8_t)2)
00717 #define PLAYER_POSITION_VELOCITY_MODE_REQ ((uint8_t)3)
00718 #define PLAYER_POSITION_RESET_ODOM_REQ ((uint8_t)4)
00719 #define PLAYER_POSITION_POSITION_MODE_REQ ((uint8_t)5)
00720 #define PLAYER_POSITION_SPEED_PID_REQ ((uint8_t)6)
00721 #define PLAYER_POSITION_POSITION_PID_REQ ((uint8_t)7)
00722 #define PLAYER_POSITION_SPEED_PROF_REQ ((uint8_t)8)
00723 #define PLAYER_POSITION_SET_ODOM_REQ ((uint8_t)9)
00724
00725
00726
00727 #define PLAYER_POSITION_RMP_VELOCITY_SCALE ((uint8_t)51)
00728 #define PLAYER_POSITION_RMP_ACCEL_SCALE ((uint8_t)52)
00729 #define PLAYER_POSITION_RMP_TURN_SCALE ((uint8_t)53)
00730 #define PLAYER_POSITION_RMP_GAIN_SCHEDULE ((uint8_t)54)
00731 #define PLAYER_POSITION_RMP_CURRENT_LIMIT ((uint8_t)55)
00732 #define PLAYER_POSITION_RMP_RST_INTEGRATORS ((uint8_t)56)
00733 #define PLAYER_POSITION_RMP_SHUTDOWN ((uint8_t)57)
00734
00735
00736 #define PLAYER_POSITION_RMP_RST_INT_RIGHT 0x01
00737 #define PLAYER_POSITION_RMP_RST_INT_LEFT 0x02
00738 #define PLAYER_POSITION_RMP_RST_INT_YAW 0x04
00739 #define PLAYER_POSITION_RMP_RST_INT_FOREAFT 0x08
00740
00741
00746 typedef struct player_position_data
00747 {
00749 int32_t xpos, ypos;
00751 int32_t yaw;
00753 int32_t xspeed, yspeed;
00755 int32_t yawspeed;
00757 uint8_t stall;
00758 } __PACKED__ player_position_data_t;
00759
00765 typedef struct player_position_cmd
00766 {
00768 int32_t xpos, ypos;
00770 int32_t yaw;
00772 int32_t xspeed, yspeed;
00774 int32_t yawspeed;
00776 uint8_t state;
00778 uint8_t type;
00779 } __PACKED__ player_position_cmd_t;
00780
00786 typedef struct player_position_geom
00787 {
00789 uint8_t subtype;
00791 int16_t pose[3];
00793 uint16_t size[2];
00794 } __PACKED__ player_position_geom_t;
00795
00796
00809 typedef struct player_position_power_config
00810 {
00812 uint8_t request;
00814 uint8_t value;
00815 } __PACKED__ player_position_power_config_t;
00816
00842 typedef struct player_position_velocitymode_config
00843 {
00845 uint8_t request;
00847 uint8_t value;
00848 } __PACKED__ player_position_velocitymode_config_t;
00849
00855 typedef struct player_position_resetodom_config
00856 {
00858 uint8_t request;
00859 } __PACKED__ player_position_resetodom_config_t;
00860
00862 typedef struct player_position_position_mode_req
00863 {
00865 uint8_t subtype;
00867 uint8_t state;
00868 } __PACKED__ player_position_position_mode_req_t;
00869
00874 typedef struct player_position_set_odom_req
00875 {
00877 uint8_t subtype;
00879 int32_t x, y;
00881 int32_t theta;
00882 }__PACKED__ player_position_set_odom_req_t;
00883
00885 typedef struct player_position_speed_pid_req
00886 {
00888 uint8_t subtype;
00890 int32_t kp, ki, kd;
00891 } __PACKED__ player_position_speed_pid_req_t;
00892
00894 typedef struct player_position_position_pid_req
00895 {
00897 uint8_t subtype;
00899 int32_t kp, ki, kd;
00900 } __PACKED__ player_position_position_pid_req_t;
00901
00903 typedef struct player_position_speed_prof_req
00904 {
00906 uint8_t subtype;
00908 int16_t speed;
00910 int16_t acc;
00911 } __PACKED__ player_position_speed_prof_req_t;
00912
00914 typedef struct player_rmp_config
00915 {
00917 uint8_t subtype;
00920 uint16_t value;
00921 } __PACKED__ player_rmp_config_t;
00922
00923
00928
00940
00941 #define PLAYER_POSITION2D_GET_GEOM_REQ ((uint8_t)1)
00942 #define PLAYER_POSITION2D_MOTOR_POWER_REQ ((uint8_t)2)
00943 #define PLAYER_POSITION2D_VELOCITY_MODE_REQ ((uint8_t)3)
00944 #define PLAYER_POSITION2D_RESET_ODOM_REQ ((uint8_t)4)
00945 #define PLAYER_POSITION2D_POSITION_MODE_REQ ((uint8_t)5)
00946 #define PLAYER_POSITION2D_SPEED_PID_REQ ((uint8_t)6)
00947 #define PLAYER_POSITION2D_POSITION_PID_REQ ((uint8_t)7)
00948 #define PLAYER_POSITION2D_SPEED_PROF_REQ ((uint8_t)8)
00949 #define PLAYER_POSITION2D_SET_ODOM_REQ ((uint8_t)9)
00950
00951
00952
00953 #define PLAYER_POSITION2D_RMP_VELOCITY_SCALE ((uint8_t)51)
00954 #define PLAYER_POSITION2D_RMP_ACCEL_SCALE ((uint8_t)52)
00955 #define PLAYER_POSITION2D_RMP_TURN_SCALE ((uint8_t)53)
00956 #define PLAYER_POSITION2D_RMP_GAIN_SCHEDULE ((uint8_t)54)
00957 #define PLAYER_POSITION2D_RMP_CURRENT_LIMIT ((uint8_t)55)
00958 #define PLAYER_POSITION2D_RMP_RST_INTEGRATORS ((uint8_t)56)
00959 #define PLAYER_POSITION2D_RMP_SHUTDOWN ((uint8_t)57)
00960
00961
00962 #define PLAYER_POSITION2D_RMP_RST_INT_RIGHT 0x01
00963 #define PLAYER_POSITION2D_RMP_RST_INT_LEFT 0x02
00964 #define PLAYER_POSITION2D_RMP_RST_INT_YAW 0x04
00965 #define PLAYER_POSITION2D_RMP_RST_INT_FOREAFT 0x08
00966
00971 typedef struct player_position2d_data
00972 {
00974 int32_t xpos, ypos;
00976 int32_t yaw;
00978 int32_t xspeed, yspeed;
00980 int32_t yawspeed;
00982 uint8_t stall;
00983 } __PACKED__ player_position2d_data_t;
00984
00990 typedef struct player_position2d_cmd
00991 {
00993 int32_t xpos, ypos;
00995 int32_t yaw;
00997 int32_t xspeed, yspeed;
00999 int32_t yawspeed;
01001 uint8_t state;
01003 uint8_t type;
01004 } __PACKED__ player_position2d_cmd_t;
01005
01011 typedef struct player_position2d_geom
01012 {
01014 uint8_t subtype;
01016 int16_t pose[3];
01018 uint16_t size[2];
01019 } __PACKED__ player_position2d_geom_t;
01020
01031 typedef struct player_position2d_power_config
01032 {
01034 uint8_t request;
01036 uint8_t value;
01037 } __PACKED__ player_position2d_power_config_t;
01038 typedef struct
01062 player_position2d_velocitymode_config
01063 {
01065 uint8_t request;
01067 uint8_t value;
01068 } __PACKED__ player_position2d_velocitymode_config_t;
01069
01070
01076 typedef struct player_position2d_resetodom_config
01077 {
01079 uint8_t request;
01080 } __PACKED__ player_position2d_resetodom_config_t;
01081
01083 typedef struct player_position2d_position_mode_req
01084 {
01086 uint8_t subtype;
01088 uint8_t state;
01089 } __PACKED__ player_position2d_position_mode_req_t;
01090
01094 typedef struct player_position2d_set_odom_req
01095 {
01097 uint8_t subtype;
01099 int32_t x, y;
01101 int32_t theta;
01102 }__PACKED__ player_position2d_set_odom_req_t;
01103
01105 typedef struct player_position2d_speed_pid_req
01106 {
01108 uint8_t subtype;
01110 int32_t kp, ki, kd;
01111 } __PACKED__ player_position2d_speed_pid_req_t;
01112
01114 typedef struct player_position2d_position_pid_req
01115 {
01117 uint8_t subtype;
01119 int32_t kp, ki, kd;
01120 } __PACKED__ player_position2d_position_pid_req_t;
01121
01123 typedef struct player_position2d_speed_prof_req
01124 {
01126 uint8_t subtype;
01128 int32_t speed;
01130 int32_t acc;
01131 } __PACKED__ player_position2d_speed_prof_req_t;
01132
01137
01147
01148 #define PLAYER_POSITION3D_GET_GEOM_REQ ((uint8_t)1)
01149 #define PLAYER_POSITION3D_MOTOR_POWER_REQ ((uint8_t)2)
01150 #define PLAYER_POSITION3D_VELOCITY_MODE_REQ ((uint8_t)3)
01151 #define PLAYER_POSITION3D_RESET_ODOM_REQ ((uint8_t)4)
01152 #define PLAYER_POSITION3D_POSITION_MODE_REQ ((uint8_t)5)
01153 #define PLAYER_POSITION3D_SPEED_PID_REQ ((uint8_t)6)
01154 #define PLAYER_POSITION3D_POSITION_PID_REQ ((uint8_t)7)
01155 #define PLAYER_POSITION3D_SPEED_PROF_REQ ((uint8_t)8)
01156 #define PLAYER_POSITION3D_SET_ODOM_REQ ((uint8_t)9)
01157
01162 typedef struct player_position3d_data
01163 {
01165 int32_t xpos, ypos, zpos;
01167 int32_t roll, pitch, yaw;
01169 int32_t xspeed, yspeed, zspeed;
01171 int32_t rollspeed, pitchspeed, yawspeed;
01173 uint8_t stall;
01174 } __PACKED__ player_position3d_data_t;
01175
01176
01181 typedef struct player_position3d_cmd
01182 {
01184 int32_t xpos, ypos, zpos;
01186 int32_t roll, pitch, yaw;
01188 int32_t xspeed, yspeed, zspeed;
01190 int32_t rollspeed, pitchspeed, yawspeed;
01192 uint8_t state;
01194 uint8_t type;
01195 } __PACKED__ player_position3d_cmd_t;
01196
01197
01203 typedef struct player_position3d_geom
01204 {
01206 uint8_t subtype;
01207
01209 int16_t pose[6];
01210
01212 uint16_t size[3];
01213
01214 } __PACKED__ player_position3d_geom_t;
01215
01216
01227 typedef struct player_position3d_power_config
01228 {
01230 uint8_t request;
01232 uint8_t value;
01233 } __PACKED__ player_position3d_power_config_t;
01234
01235
01237 typedef struct player_position3d_position_mode_req
01238 {
01240 uint8_t subtype;
01242 uint8_t state;
01243 } __PACKED__ player_position3d_position_mode_req_t;
01244
01245
01253 typedef struct player_position3d_velocitymode_config
01254 {
01256 uint8_t request;
01258 uint8_t value;
01259 } __PACKED__ player_position3d_velocitymode_config_t;
01260
01261
01265 typedef struct player_position3d_set_odom_req
01266 {
01268 uint8_t subtype;
01270 int32_t x, y, z;
01272 int32_t roll, pitch, yaw;
01273 }__PACKED__ player_position3d_set_odom_req_t;
01274
01275
01280 typedef struct player_position3d_resetodom_config
01281 {
01283 uint8_t request;
01284 } __PACKED__ player_position3d_resetodom_config_t;
01285
01286
01288 typedef struct player_position3d_speed_pid_req
01289 {
01291 uint8_t subtype;
01293 int32_t kp, ki, kd;
01294 } __PACKED__ player_position3d_speed_pid_req_t;
01295
01296
01298 typedef struct player_position3d_position_pid_req
01299 {
01301 uint8_t subtype;
01303 int32_t kp, ki, kd;
01304 } __PACKED__ player_position3d_position_pid_req_t;
01305
01307 typedef struct player_position3d_speed_prof_req
01308 {
01310 uint8_t subtype;
01312 int32_t speed;
01314 int32_t acc;
01315 } __PACKED__ player_position3d_speed_prof_req_t;
01316
01320
01331 #define PLAYER_SONAR_MAX_SAMPLES 64
01332
01333 #define PLAYER_SONAR_GET_GEOM_REQ ((uint8_t)1)
01334 #define PLAYER_SONAR_POWER_REQ ((uint8_t)2)
01335
01340 typedef struct player_sonar_data
01341 {
01343 uint16_t range_count;
01345 uint16_t ranges[PLAYER_SONAR_MAX_SAMPLES];
01346 } __PACKED__ player_sonar_data_t;
01347
01348
01354 typedef struct player_sonar_geom
01355 {
01357 uint8_t subtype;
01359 uint16_t pose_count;
01361 int16_t poses[PLAYER_SONAR_MAX_SAMPLES][3];
01362 } __PACKED__ player_sonar_geom_t;
01363
01369 typedef struct player_sonar_power_config
01370 {
01372 uint8_t subtype;
01374 uint8_t value;
01375 } __PACKED__ player_sonar_power_config_t;
01376
01381
01405 #define PLAYER_LASER_MAX_SAMPLES 401
01406
01407
01408 #define PLAYER_LASER_GET_GEOM 0x01
01409 #define PLAYER_LASER_SET_CONFIG 0x02
01410 #define PLAYER_LASER_GET_CONFIG 0x03
01411 #define PLAYER_LASER_POWER_CONFIG 0x04
01412
01416 typedef struct player_laser_data
01417 {
01420 int16_t min_angle, max_angle;
01422 uint16_t resolution;
01424 uint16_t range_res;
01426 uint16_t range_count;
01428 uint16_t ranges[PLAYER_LASER_MAX_SAMPLES];
01430 uint8_t intensity[PLAYER_LASER_MAX_SAMPLES];
01431 } __PACKED__ player_laser_data_t;
01432
01438 typedef struct player_laser_geom
01439 {
01441 uint8_t subtype;
01443 int16_t pose[3];
01445 int16_t size[2];
01446 } __PACKED__ player_laser_geom_t;
01447
01454 typedef struct player_laser_config
01455 {
01459 uint8_t subtype;
01460
01463 int16_t min_angle, max_angle;
01464
01467 uint16_t resolution;
01468
01470 uint16_t range_res;
01471
01473 uint8_t intensity;
01474
01475 } __PACKED__ player_laser_config_t;
01476
01477
01482 typedef struct player_laser_power_config
01483 {
01485 uint8_t subtype;
01487 uint8_t value;
01488 } __PACKED__ player_laser_power_config_t;
01489
01493
01505 #define PLAYER_BLOBFINDER_MAX_BLOBS 256
01506
01507
01508 #define PLAYER_BLOBFINDER_SET_COLOR_REQ ((uint8_t)1)
01509 #define PLAYER_BLOBFINDER_SET_IMAGER_PARAMS_REQ ((uint8_t)2)
01510
01511
01513 typedef struct player_blobfinder_blob
01514 {
01516 int16_t id;
01519 uint32_t color;
01521 uint32_t area;
01523 uint16_t x, y;
01525 uint16_t left, right, top, bottom;
01527 uint16_t range;
01528 } __PACKED__ player_blobfinder_blob_t;
01529
01533 typedef struct player_blobfinder_data
01534 {
01536 uint16_t width, height;
01538 uint16_t blob_count;
01539 player_blobfinder_blob_t blobs[PLAYER_BLOBFINDER_MAX_BLOBS];
01540 } __PACKED__ player_blobfinder_data_t;
01541
01542
01552 typedef struct player_blobfinder_color_config
01553 {
01555 uint8_t subtype;
01557 int16_t rmin, rmax;
01558 int16_t gmin, gmax;
01559 int16_t bmin, bmax;
01560 } __PACKED__ player_blobfinder_color_config_t;
01561
01562
01576 typedef struct player_blobfinder_imager_config
01577 {
01579 uint8_t subtype;
01581 int16_t brightness;
01582 int16_t contrast;
01587 int8_t colormode;
01589 int8_t autogain;
01590 } __PACKED__ player_blobfinder_imager_config_t;
01591
01596
01607 #define PLAYER_PTZ_GENERIC_CONFIG_REQ ((uint8_t)1)
01608
01609 #define PLAYER_PTZ_CONTROL_MODE_REQ ((uint8_t)2)
01610
01611 #define PLAYER_PTZ_AUTOSERVO ((uint8_t)3)
01612
01615 #define PLAYER_PTZ_MAX_CONFIG_LEN 32
01616
01618 #define PLAYER_PTZ_VELOCITY_CONTROL 0
01619
01620 #define PLAYER_PTZ_POSITION_CONTROL 1
01621
01626 typedef struct player_ptz_data
01627 {
01629 int16_t pan;
01631 int16_t tilt;
01633 int16_t zoom;
01635 int16_t panspeed, tiltspeed;
01636 } __PACKED__ player_ptz_data_t;
01637
01642 typedef struct player_ptz_cmd
01643 {
01645 int16_t pan;
01647 int16_t tilt;
01649 int16_t zoom;
01651 int16_t panspeed, tiltspeed;
01652 } __PACKED__ player_ptz_cmd_t;
01653
01659 typedef struct player_ptz_generic_config
01660 {
01662 uint8_t subtype;
01664 uint16_t length;
01666 uint8_t config[PLAYER_PTZ_MAX_CONFIG_LEN];
01667 } __PACKED__ player_ptz_generic_config_t;
01668
01675 typedef struct player_ptz_controlmode_config
01676 {
01678 uint8_t subtype;
01681 uint8_t mode;
01682 } __PACKED__ player_ptz_velocitymode_config_t;
01683
01704 #define PLAYER_CAMERA_IMAGE_WIDTH 640
01705 #define PLAYER_CAMERA_IMAGE_HEIGHT 480
01706 #define PLAYER_CAMERA_IMAGE_SIZE (640 * 480 * 4)
01707
01709 #define PLAYER_CAMERA_FORMAT_MONO8 1
01710
01711 #define PLAYER_CAMERA_FORMAT_MONO16 2
01712
01713 #define PLAYER_CAMERA_FORMAT_RGB565 4
01714
01715 #define PLAYER_CAMERA_FORMAT_RGB888 5
01716
01717
01718 #define PLAYER_CAMERA_COMPRESS_RAW 0
01719 #define PLAYER_CAMERA_COMPRESS_JPEG 1
01720
01722 typedef struct player_camera_data
01723 {
01725 uint16_t width, height;
01727 uint8_t bpp;
01729 uint8_t format;
01733 uint16_t fdiv;
01736 uint8_t compression;
01738 uint32_t image_size;
01742 uint8_t image[PLAYER_CAMERA_IMAGE_SIZE];
01743 } __PACKED__ player_camera_data_t;
01744
01757 #define AUDIO_DATA_BUFFER_SIZE 20
01758 #define AUDIO_COMMAND_BUFFER_SIZE 3*sizeof(short)
01759
01760
01767 typedef struct player_audio_data
01768 {
01770 uint16_t frequency0, amplitude0;
01772 uint16_t frequency1, amplitude1;
01774 uint16_t frequency2, amplitude2;
01776 uint16_t frequency3, amplitude3;
01778 uint16_t frequency4, amplitude4;
01779 } __PACKED__ player_audio_data_t;
01780
01786 typedef struct player_audio_cmd
01787 {
01789 uint16_t frequency;
01791 uint16_t amplitude;
01793 uint16_t duration;
01794 } __PACKED__ player_audio_cmd_t;
01795
01808 #define PLAYER_AUDIODSP_SET_CONFIG 0x01
01809 #define PLAYER_AUDIODSP_GET_CONFIG 0x02
01810 #define PLAYER_AUDIODSP_PLAY_TONE 0x03
01811 #define PLAYER_AUDIODSP_PLAY_CHIRP 0x04
01812 #define PLAYER_AUDIODSP_REPLAY 0x05
01813
01814
01821 typedef struct player_audiodsp_data
01822 {
01824 uint16_t freq[5];
01826 uint16_t amp[5];
01827
01828 } __PACKED__ player_audiodsp_data_t;
01829
01836 typedef struct player_audiodsp_cmd
01837 {
01843 uint8_t subtype;
01845 uint16_t frequency;
01847 uint16_t amplitude;
01849 uint32_t duration;
01851 unsigned char bitString[PLAYER_MAX_DEVICE_STRING_LEN];
01853 uint16_t bitStringLen;
01854 } __PACKED__ player_audiodsp_cmd_t;
01855
01874 typedef struct player_audiodsp_config
01875 {
01879 uint8_t subtype;
01881 int16_t sampleFormat;
01883 uint16_t sampleRate;
01885 uint8_t channels;
01886 } __PACKED__ player_audiodsp_config_t;
01887
01899 #define PLAYER_AUDIOMIXER_SET_MASTER 0x01
01900 #define PLAYER_AUDIOMIXER_SET_PCM 0x02
01901 #define PLAYER_AUDIOMIXER_SET_LINE 0x03
01902 #define PLAYER_AUDIOMIXER_SET_MIC 0x04
01903 #define PLAYER_AUDIOMIXER_SET_IGAIN 0x05
01904 #define PLAYER_AUDIOMIXER_SET_OGAIN 0x06
01905
01906
01916 typedef struct player_audiomixer_cmd
01917 {
01920 uint8_t subtype;
01921 uint16_t left;
01922 uint16_t right;
01923
01924 } __PACKED__ player_audiomixer_cmd_t;
01925
01931 typedef struct player_audiomixer_config
01932 {
01933 uint8_t subtype;
01934 uint16_t masterLeft, masterRight;
01935 uint16_t pcmLeft, pcmRight;
01936 uint16_t lineLeft, lineRight;
01937 uint16_t micLeft, micRight;
01938 uint16_t iGain, oGain;
01939 } __PACKED__ player_audiomixer_config_t;
01940
01953
01954 #define PLAYER_WAVEFORM_DATA_MAX 4096
01955
01960 typedef struct player_waveform_data
01961 {
01963 uint32_t rate;
01965 uint16_t depth;
01967 uint32_t samples;
01969 uint8_t data[ PLAYER_WAVEFORM_DATA_MAX ];
01970 } __PACKED__ player_waveform_data_t;
01971
01990 typedef struct player_blinkenlight_data
01991 {
01993 uint8_t enable;
01995 uint16_t period_ms;
01996 } __PACKED__ player_blinkenlight_data_t;
01997
02002 typedef player_blinkenlight_data_t player_blinkenlight_cmd_t;
02003
02019 #define PLAYER_FIDUCIAL_MAX_SAMPLES 32
02020
02022 #define PLAYER_FIDUCIAL_MAX_MSG_LEN 32
02023
02024
02025 #define PLAYER_FIDUCIAL_GET_GEOM 0x01
02026 #define PLAYER_FIDUCIAL_GET_FOV 0x02
02027 #define PLAYER_FIDUCIAL_SET_FOV 0x03
02028 #define PLAYER_FIDUCIAL_SEND_MSG 0x04
02029 #define PLAYER_FIDUCIAL_RECV_MSG 0x05
02030 #define PLAYER_FIDUCIAL_EXCHANGE_MSG 0x06
02031 #define PLAYER_FIDUCIAL_GET_ID 0x07
02032 #define PLAYER_FIDUCIAL_SET_ID 0x08
02033
02034
02038 typedef struct player_fiducial_item
02039 {
02042 int16_t id;
02044 int32_t pos[3];
02046 int32_t rot[3];
02048 int32_t upos[3];
02051 int32_t urot[3];
02052 } __PACKED__ player_fiducial_item_t;
02053
02054
02058 typedef struct player_fiducial_data
02059 {
02061 uint16_t count;
02063 player_fiducial_item_t fiducials[PLAYER_FIDUCIAL_MAX_SAMPLES];
02064
02065 } __PACKED__ player_fiducial_data_t;
02066
02067
02068
02075 typedef struct player_fiducial_geom
02076 {
02078 uint8_t subtype;
02081 int16_t pose[3];
02083 uint16_t size[2];
02085 uint16_t fiducial_size[2];
02086 } __PACKED__ player_fiducial_geom_t;
02087
02096 typedef struct player_fiducial_fov
02097 {
02099 uint8_t subtype;
02101 uint16_t min_range;
02103 uint16_t max_range;
02105 uint16_t view_angle;
02106 } __PACKED__ player_fiducial_fov_t;
02107
02108
02125 typedef struct player_fiducial_id
02126 {
02128 uint8_t subtype;
02130 uint32_t id;
02131 } __PACKED__ player_fiducial_id_t;
02132
02133
02134
02165 typedef struct player_fiducial_msg
02166 {
02168 int32_t target_id;
02170 uint8_t bytes[PLAYER_FIDUCIAL_MAX_MSG_LEN];
02172 uint8_t len;
02175 uint8_t intensity;
02176 } __PACKED__ player_fiducial_msg_t;
02177
02178
02182 typedef struct player_fiducial_msg_rx_req
02183 {
02185 uint8_t subtype;
02188 uint8_t consume;
02189 } __PACKED__ player_fiducial_msg_rx_req_t;
02190
02194 typedef struct player_fiducial_msg_tx_req
02195 {
02197 uint8_t subtype;
02200 uint8_t consume;
02202 player_fiducial_msg_t msg;
02203 } __PACKED__ player_fiducial_msg_tx_req_t;
02204
02210 typedef struct player_fiducial_msg_txrx_req
02211 {
02213 uint8_t subtype;
02215 player_fiducial_msg_t msg;
02218 uint8_t consume_send;
02221 uint8_t consume_reply;
02222 } __PACKED__ player_fiducial_msg_txrx_req_t;
02223
02238 #define PLAYER_SPEECH_MAX_STRING_LEN 256
02239
02240
02245 typedef struct player_speech_cmd
02246 {
02248 uint8_t string[PLAYER_SPEECH_MAX_STRING_LEN];
02249 } __PACKED__ player_speech_cmd_t;
02250
02269 typedef struct player_gps_data
02270 {
02272 uint32_t time_sec, time_usec;
02276 int32_t latitude;
02280 int32_t longitude;
02283 int32_t altitude;
02285 int32_t utm_e, utm_n;
02287 uint8_t quality;
02289 uint8_t num_sats;
02291 uint16_t hdop;
02293 uint16_t vdop;
02295 uint32_t err_horz;
02297 uint32_t err_vert;
02298 } __PACKED__ player_gps_data_t;
02299
02313 #define PLAYER_BUMPER_MAX_SAMPLES 32
02314
02315 #define PLAYER_BUMPER_GET_GEOM_REQ ((uint8_t)1)
02316
02320 typedef struct player_bumper_data
02321 {
02323 uint8_t bumper_count;
02325 uint8_t bumpers[PLAYER_BUMPER_MAX_SAMPLES];
02326 } __PACKED__ player_bumper_data_t;
02327
02329 typedef struct player_bumper_define
02330 {
02332 int16_t x_offset, y_offset, th_offset;
02334 uint16_t length;
02336 uint16_t radius;
02337 } __PACKED__ player_bumper_define_t;
02338
02344 typedef struct player_bumper_geom
02345 {
02347 uint8_t subtype;
02349 uint16_t bumper_count;
02351 player_bumper_define_t bumper_def[PLAYER_BUMPER_MAX_SAMPLES];
02352 } __PACKED__ player_bumper_geom_t;
02353
02367
02368 #define PLAYER_TRUTH_GET_POSE 0x00
02369 #define PLAYER_TRUTH_SET_POSE 0x01
02370 #define PLAYER_TRUTH_SET_POSE_ON_ROOT 0x02
02371 #define PLAYER_TRUTH_GET_FIDUCIAL_ID 0x03
02372 #define PLAYER_TRUTH_SET_FIDUCIAL_ID 0x04
02373
02378 typedef struct player_truth_data
02379 {
02381 int32_t pos[3];
02383 int32_t rot[3];
02384 } __PACKED__ player_truth_data_t;
02385
02394 typedef struct player_truth_pose
02395 {
02400 uint8_t subtype;
02402 int32_t pos[3];
02404 int32_t rot[3];
02405 } __PACKED__ player_truth_pose_t;
02406
02414 typedef struct player_truth_fiducial_id
02415 {
02418 uint8_t subtype;
02420 int16_t id;
02421 } __PACKED__ player_truth_fiducial_id_t;
02422
02446 #define PLAYER_SIMULATION_SET_POSE2D 0x00
02447 #define PLAYER_SIMULATION_GET_POSE2D 0x01
02448
02450 #define PLAYER_SIMULATION_IDENTIFIER_MAXLEN 64
02451
02452
02457 typedef struct player_simulation_data
02458 {
02460 uint8_t data;
02461 } __PACKED__ player_simulation_data_t;
02462
02467 typedef struct player_simulation_cmd
02468 {
02470 uint8_t cmd;
02471 } __PACKED__ player_simulation_cmd_t;
02472
02473
02484 typedef struct player_simulation_pose2d_req
02485 {
02489 uint8_t subtype;
02490
02492 char name[PLAYER_SIMULATION_IDENTIFIER_MAXLEN];
02493
02495 int32_t x, y, a;
02496 } __PACKED__ player_simulation_pose2d_req_t;
02497
02513 typedef struct player_dio_data
02514 {
02516 uint8_t count;
02518 uint32_t digin;
02519 } __PACKED__ player_dio_data_t;
02520
02521
02526 typedef struct player_dio_cmd
02527 {
02529 uint8_t count;
02530
02531 uint32_t digout;
02532 } __PACKED__ player_dio_cmd_t;
02533
02549 #define PLAYER_AIO_MAX_SAMPLES 8
02550
02555 typedef struct player_aio_data
02556 {
02558 uint8_t count;
02560 int32_t anin[PLAYER_AIO_MAX_SAMPLES];
02561 } __PACKED__ player_aio_data_t;
02562
02582 typedef struct player_joystick_data
02583 {
02585 int16_t xpos, ypos;
02587 int16_t xscale, yscale;
02589 uint16_t buttons;
02590 } __PACKED__ player_joystick_data_t;
02591
02607 #define PLAYER_WIFI_MAX_LINKS 32
02608
02610 #define PLAYER_WIFI_QUAL_DBM 1
02611
02612 #define PLAYER_WIFI_QUAL_REL 2
02613
02614 #define PLAYER_WIFI_QUAL_UNKNOWN 3
02615
02617 #define PLAYER_WIFI_MODE_UNKNOWN 0
02618
02619 #define PLAYER_WIFI_MODE_AUTO 1
02620
02621 #define PLAYER_WIFI_MODE_ADHOC 2
02622
02623 #define PLAYER_WIFI_MODE_INFRA 3
02624
02625 #define PLAYER_WIFI_MODE_MASTER 4
02626
02627 #define PLAYER_WIFI_MODE_REPEAT 5
02628
02629 #define PLAYER_WIFI_MODE_SECOND 6
02630
02631
02632 #define PLAYER_WIFI_MAC_REQ ((uint8_t)1)
02633 #define PLAYER_WIFI_IWSPY_ADD_REQ ((uint8_t)10)
02634 #define PLAYER_WIFI_IWSPY_DEL_REQ ((uint8_t)11)
02635 #define PLAYER_WIFI_IWSPY_PING_REQ ((uint8_t)12)
02636
02642 typedef struct player_wifi_link
02643 {
02645 char mac[32];
02647 char ip[32];
02649 char essid[32];
02651 uint8_t mode;
02653 uint16_t freq;
02655 uint8_t encrypt;
02659 uint16_t qual, level, noise;
02660 } __PACKED__ player_wifi_link_t;
02661
02662
02666 typedef struct player_wifi_data
02667 {
02669 player_wifi_link_t links[PLAYER_WIFI_MAX_LINKS];
02671 uint16_t link_count;
02673 uint32_t throughput;
02675 int32_t bitrate;
02677 uint8_t mode;
02679 uint8_t qual_type;
02681 uint16_t maxqual, maxlevel, maxnoise;
02683 char ap[32];
02684 } __PACKED__ player_wifi_data_t;
02685
02687 typedef struct player_wifi_mac_req
02688 {
02689 uint8_t subtype;
02690 } __PACKED__ player_wifi_mac_req_t;
02691
02693 typedef struct player_wifi_iwspy_addr_req
02694 {
02695 uint8_t subtype;
02696 char address[32];
02697 } __PACKED__ player_wifi_iwspy_addr_req_t;
02698
02714 #define PLAYER_IR_MAX_SAMPLES 32
02715
02716 #define PLAYER_IR_POSE_REQ ((uint8_t)1)
02717 #define PLAYER_IR_POWER_REQ ((uint8_t)2)
02718
02722 typedef struct player_ir_data
02723 {
02725 uint16_t range_count;
02727 uint16_t voltages[PLAYER_IR_MAX_SAMPLES];
02729 uint16_t ranges[PLAYER_IR_MAX_SAMPLES];
02730 } __PACKED__ player_ir_data_t;
02731
02733 typedef struct player_ir_pose
02734 {
02736 uint16_t pose_count;
02738 int16_t poses[PLAYER_IR_MAX_SAMPLES][3];
02739 } __PACKED__ player_ir_pose_t;
02740
02741
02746 typedef struct player_ir_pose_req
02747 {
02749 uint8_t subtype;
02751 player_ir_pose_t poses;
02752 } __PACKED__ player_ir_pose_req_t;
02753
02758 typedef struct player_ir_power_req
02759 {
02761 uint8_t subtype;
02763 uint8_t state;
02764 } __PACKED__ player_ir_power_req_t;
02765
02785 #define PLAYER_LOCALIZE_MAX_HYPOTHS 10
02786
02787
02788 #define PLAYER_LOCALIZE_SET_POSE_REQ ((uint8_t)1)
02789 #define PLAYER_LOCALIZE_GET_CONFIG_REQ ((uint8_t)2)
02790 #define PLAYER_LOCALIZE_SET_CONFIG_REQ ((uint8_t)3)
02791 #define PLAYER_LOCALIZE_GET_PARTICLES_REQ ((uint8_t)4)
02792
02798 typedef struct player_localize_hypoth
02799 {
02801 int32_t mean[3];
02803 int64_t cov[3][3];
02805 uint32_t alpha;
02806 } __PACKED__ player_localize_hypoth_t;
02807
02812 typedef struct player_localize_data
02813 {
02815 uint16_t pending_count;
02817 uint32_t pending_time_sec, pending_time_usec;
02819 uint32_t hypoth_count;
02821 player_localize_hypoth_t hypoths[PLAYER_LOCALIZE_MAX_HYPOTHS];
02822 } __PACKED__ player_localize_data_t;
02823
02824
02829 typedef struct player_localize_set_pose
02830 {
02832 uint8_t subtype;
02834 int32_t mean[3];
02836 int64_t cov[3][3];
02837
02838 } __PACKED__ player_localize_set_pose_t;
02839
02840
02848 typedef struct player_localize_config
02849 {
02852 uint8_t subtype;
02855 uint32_t num_particles;
02856 } __PACKED__ player_localize_config_t;
02857
02858 #define PLAYER_LOCALIZE_PARTICLES_MAX 100
02859
02860 typedef struct player_localize_particle
02861 {
02863 int32_t pose[3];
02865 uint32_t alpha;
02866 } __PACKED__ player_localize_particle_t;
02867
02871 typedef struct player_localize_get_particles
02872 {
02873 uint8_t subtype;
02875 int32_t mean[3];
02877 uint64_t variance;
02879 uint32_t num_particles;
02881 player_localize_particle_t particles[PLAYER_LOCALIZE_PARTICLES_MAX];
02882 } __PACKED__ player_localize_get_particles_t;
02883
02898 #define PLAYER_MAP_MAX_CELLS_PER_TILE (PLAYER_MAX_REQREP_SIZE - 17)
02899
02900 #define PLAYER_MAP_GET_INFO_REQ ((uint8_t)1)
02901 #define PLAYER_MAP_GET_DATA_REQ ((uint8_t)2)
02902
02909 typedef struct player_map_info
02910 {
02912 uint8_t subtype;
02914 uint32_t scale;
02916 uint32_t width, height;
02917 } __PACKED__ player_map_info_t;
02918
02925 typedef struct player_map_data
02926 {
02928 uint8_t subtype;
02930 uint32_t col, row;
02932 uint32_t width, height;
02934 int8_t data[PLAYER_MAX_REQREP_SIZE - 17];
02935 } __PACKED__ player_map_data_t;
02936
02937
02958 #define MCOM_DATA_LEN 128
02959 #define MCOM_COMMAND_BUFFER_SIZE (sizeof(player_mcom_config_t))
02960 #define MCOM_DATA_BUFFER_SIZE 0
02961
02962 #define MCOM_N_BUFS 10
02963
02964 #define MCOM_CHANNEL_LEN 8
02965
02966 #define MCOM_EMPTY_STRING "(EMPTY)"
02967
02968 #define PLAYER_MCOM_PUSH_REQ 0
02969 #define PLAYER_MCOM_POP_REQ 1
02970 #define PLAYER_MCOM_READ_REQ 2
02971 #define PLAYER_MCOM_CLEAR_REQ 3
02972 #define PLAYER_MCOM_SET_CAPACITY_REQ 4
02973
02974
02976 typedef struct player_mcom_data
02977 {
02979 char full;
02981 char data[MCOM_DATA_LEN];
02982 } __PACKED__ player_mcom_data_t;
02983
02984
02986 typedef struct player_mcom_config
02987 {
02989 uint8_t command;
02991 uint16_t type;
02993 char channel[MCOM_CHANNEL_LEN];
02995 player_mcom_data_t data;
02996 } __PACKED__ player_mcom_config_t;
02997
02999 typedef struct player_mcom_return
03000 {
03002 uint16_t type;
03004 char channel[MCOM_CHANNEL_LEN];
03006 player_mcom_data_t data;
03007 } __PACKED__ player_mcom_return_t;
03008
03026 #define PLAYER_NOMAD_SONAR_COUNT 16
03027 #define PLAYER_NOMAD_BUMPER_COUNT 16
03028 #define PLAYER_NOMAD_IR_COUNT 16
03029
03034 typedef struct player_nomad_data
03035 {
03037 int32_t x, y;
03039 int32_t a;
03041 int32_t vel_trans;
03043 int32_t vel_steer;
03045 int32_t vel_turret;
03047 uint16_t sonar[PLAYER_NOMAD_SONAR_COUNT];
03049 uint16_t ir[PLAYER_NOMAD_IR_COUNT];
03051 uint8_t bumper[PLAYER_NOMAD_BUMPER_COUNT];
03052 } __PACKED__ player_nomad_data_t;
03053
03064 typedef struct player_nomad_cmd
03065 {
03066 int32_t vel_trans, vel_steer, vel_turret;
03067 } __PACKED__ player_nomad_cmd_t;
03068
03069
03088 typedef struct player_sound_cmd
03089 {
03091 uint16_t index;
03092 } __PACKED__ player_sound_cmd_t;
03093
03111 typedef struct player_energy_data
03112 {
03114 int32_t mjoules;
03117 int32_t mwatts;
03122 int8_t charging;
03123
03124 } __PACKED__ player_energy_data_t;
03125
03127 typedef struct player_energy_command
03128 {
03131 uint8_t enable_input;
03134 uint8_t enable_output;
03135 } __PACKED__ player_energy_chargepolicy_config_t;
03136
03148 #define PLAYER_PLANNER_GET_WAYPOINTS_REQ ((uint8_t)10)
03149 #define PLAYER_PLANNER_ENABLE_REQ ((uint8_t)11)
03150
03152 #define PLAYER_PLANNER_MAX_WAYPOINTS 128
03153
03158 typedef struct player_planner_data
03159 {
03161 uint8_t valid;
03163 uint8_t done;
03165 int32_t px,py,pa;
03167 int32_t gx,gy,ga;
03169 int32_t wx,wy,wa;
03173 int16_t curr_waypoint;
03175 uint16_t waypoint_count;
03176 } __PACKED__ player_planner_data_t;
03177
03181 typedef struct player_planner_cmd
03182 {
03184 int32_t gx,gy,ga;
03185 } __PACKED__ player_planner_cmd_t;
03186
03188 typedef struct player_planner_waypoint
03189 {
03190 int32_t x,y,a;
03191 } __PACKED__ player_planner_waypoint_t;
03192
03194 typedef struct player_planner_waypoints_req
03195 {
03197 uint8_t subtype;
03199 uint16_t count;
03200 player_planner_waypoint_t waypoints[PLAYER_PLANNER_MAX_WAYPOINTS];
03201 } __PACKED__ player_planner_waypoints_req_t;
03202
03204 typedef struct player_planner_enable_req
03205 {
03207 uint8_t subtype;
03209 uint8_t state;
03210 } __PACKED__ player_planner_enable_req_t;
03211
03225
03226 #define PLAYER_LOG_SET_WRITE_STATE_REQ 1
03227 #define PLAYER_LOG_SET_READ_STATE_REQ 2
03228 #define PLAYER_LOG_GET_STATE_REQ 3
03229 #define PLAYER_LOG_SET_READ_REWIND_REQ 4
03230 #define PLAYER_LOG_SET_FILENAME 5
03231
03232
03233 #define PLAYER_LOG_TYPE_READ 1
03234 #define PLAYER_LOG_TYPE_WRITE 2
03235
03239 typedef struct player_log_set_write_state
03240 {
03242 uint8_t subtype;
03244 uint8_t state;
03245 } __PACKED__ player_log_set_write_state_t;
03246
03250 typedef struct player_log_set_read_state
03251 {
03253 uint8_t subtype;
03255 uint8_t state;
03256 } __PACKED__ player_log_set_read_state_t;
03257
03262 typedef struct player_log_set_read_rewind
03263 {
03265 uint8_t subtype;
03266 } __PACKED__ player_log_set_read_rewind_t;
03267
03271 typedef struct player_log_get_state
03272 {
03274 uint8_t subtype;
03277 uint8_t type;
03279 uint8_t state;
03280 } __PACKED__ player_log_get_state_t;
03281
03285 typedef struct player_log_set_filename
03286 {
03288 uint8_t subtype;
03290 uint8_t filename[256];
03291 } __PACKED__ player_log_set_filename_t;
03292
03297
03308 #define SPEECH_RECOGNITION_TEXT_LEN 256
03309
03313 typedef struct player_speech_recognition_data
03314 {
03315 char text[SPEECH_RECOGNITION_TEXT_LEN];
03316 } __PACKED__ player_speech_recognition_data_t;
03317
03318
03323 #endif