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
00028
00051 #ifndef PLAYERC_H
00052 #define PLAYERC_H
00053
00054 #include <netinet/in.h>
00055 #include <stdio.h>
00056
00057 #include <libplayerc/playercconfig.h>
00058
00059 #ifdef HAVE_GEOS
00060 #ifndef GEOS_VERSION_MAJOR
00061 #include <geos_c.h>
00062 #endif
00063 #else
00064 typedef void * GEOSGeom;
00065 #endif
00066
00067
00068
00069 #include <libplayercore/player.h>
00070 #include <libplayercore/playercommon.h>
00071 #include <libplayercore/error.h>
00072 #include <libplayercore/interface_util.h>
00073 #include <libplayerxdr/playerxdr.h>
00074 #include <libplayerxdr/functiontable.h>
00075
00076 #ifndef MIN
00077 #define MIN(a,b) ((a < b) ? a : b)
00078 #endif
00079 #ifndef MAX
00080 #define MAX(a,b) ((a > b) ? a : b)
00081 #endif
00082
00083 #ifdef __cplusplus
00084 extern "C" {
00085 #endif
00086
00087
00088
00089
00090
00091
00093 #define PLAYERC_OPEN_MODE PLAYER_OPEN_MODE
00094 #define PLAYERC_CLOSE_MODE PLAYER_CLOSE_MODE
00095 #define PLAYERC_ERROR_MODE PLAYER_ERROR_MODE
00096
00097
00099 #define PLAYERC_DATAMODE_PUSH PLAYER_DATAMODE_PUSH
00100 #define PLAYERC_DATAMODE_PULL PLAYER_DATAMODE_PULL
00101
00103 #define PLAYERC_TRANSPORT_TCP 1
00104 #define PLAYERC_TRANSPORT_UDP 2
00105
00106 #define PLAYERC_QUEUE_RING_SIZE 512
00107
00321
00327
00328
00333 const char *playerc_error_str(void);
00334
00336
00337
00339
00340
00342 int playerc_add_xdr_ftable(playerxdr_function_t *flist, int replace);
00343
00345
00346
00347
00348
00349 struct _playerc_client_t;
00350 struct _playerc_device_t;
00351
00352
00353
00354
00355 struct pollfd;
00356
00357
00358
00369
00370 typedef struct
00371 {
00372 player_msghdr_t header;
00373 void *data;
00374 } playerc_client_item_t;
00375
00376
00377
00378 typedef struct
00379 {
00380
00381 int client_count;
00382 struct _playerc_client_t *client[128];
00383
00384
00385 struct pollfd* pollfd;
00386
00387
00388 double time;
00389
00390 } playerc_mclient_t;
00391
00392
00393 playerc_mclient_t *playerc_mclient_create(void);
00394
00395
00396 void playerc_mclient_destroy(playerc_mclient_t *mclient);
00397
00398
00399 int playerc_mclient_addclient(playerc_mclient_t *mclient, struct _playerc_client_t *client);
00400
00401
00402
00403 int playerc_mclient_peek(playerc_mclient_t *mclient, int timeout);
00404
00405
00406
00407 int playerc_mclient_read(playerc_mclient_t *mclient, int timeout);
00408
00410
00411
00412
00413
00426 typedef void (*playerc_putmsg_fn_t) (void *device, char *header, char *data);
00427
00429 typedef void (*playerc_callback_fn_t) (void *data);
00430
00431
00435 typedef struct
00436 {
00438 player_devaddr_t addr;
00439
00441 char drivername[PLAYER_MAX_DRIVER_STRING_LEN];
00442
00443 } playerc_device_info_t;
00444
00445
00447 typedef struct _playerc_client_t
00448 {
00451 void *id;
00452
00454 char *host;
00455 int port;
00456 int transport;
00457 struct sockaddr_in server;
00458
00462 int retry_limit;
00463
00466 double retry_time;
00467
00469 uint32_t overflow_count;
00470
00471
00473 int sock;
00474
00476 uint8_t mode;
00477
00480 int data_requested;
00481
00484 int data_received;
00485
00486
00489 playerc_device_info_t devinfos[PLAYER_MAX_DEVICES];
00490 int devinfo_count;
00491
00493 struct _playerc_device_t *device[PLAYER_MAX_DEVICES];
00494 int device_count;
00495
00497 playerc_client_item_t qitems[PLAYERC_QUEUE_RING_SIZE];
00498 int qfirst, qlen, qsize;
00499
00501 char *data;
00502 char *write_xdrdata;
00503 char *read_xdrdata;
00504 size_t read_xdrdata_len;
00505
00506
00508 double datatime;
00510 double lasttime;
00511
00512 double request_timeout;
00513
00514 } playerc_client_t;
00515
00516
00532 playerc_client_t *playerc_client_create(playerc_mclient_t *mclient,
00533 const char *host, int port);
00534
00540 void playerc_client_destroy(playerc_client_t *client);
00541
00546 void playerc_client_set_transport(playerc_client_t* client,
00547 unsigned int transport);
00548
00557 int playerc_client_connect(playerc_client_t *client);
00558
00567 int playerc_client_disconnect(playerc_client_t *client);
00568
00575 int playerc_client_disconnect_retry(playerc_client_t *client);
00576
00591 int playerc_client_datamode(playerc_client_t *client, uint8_t mode);
00592
00604 int playerc_client_requestdata(playerc_client_t* client);
00605
00628 int playerc_client_set_replace_rule(playerc_client_t *client, int interf, int index, int type, int subtype, int replace);
00629
00630
00633 int playerc_client_adddevice(playerc_client_t *client, struct _playerc_device_t *device);
00634
00635
00638 int playerc_client_deldevice(playerc_client_t *client, struct _playerc_device_t *device);
00639
00642 int playerc_client_addcallback(playerc_client_t *client, struct _playerc_device_t *device,
00643 playerc_callback_fn_t callback, void *data);
00644
00647 int playerc_client_delcallback(playerc_client_t *client, struct _playerc_device_t *device,
00648 playerc_callback_fn_t callback, void *data);
00649
00661 int playerc_client_get_devlist(playerc_client_t *client);
00662
00665 int playerc_client_subscribe(playerc_client_t *client, int code, int index,
00666 int access, char *drivername, size_t len);
00667
00670 int playerc_client_unsubscribe(playerc_client_t *client, int code, int index);
00671
00682 int playerc_client_request(playerc_client_t *client,
00683 struct _playerc_device_t *device, uint8_t reqtype,
00684 const void *req_data, void **rep_data);
00685
00696
00697
00698
00710 int playerc_client_peek(playerc_client_t *client, int timeout);
00711
00724 int playerc_client_internal_peek(playerc_client_t *client, int timeout);
00725
00737 void *playerc_client_read(playerc_client_t *client);
00738
00739
00740
00741 int playerc_client_read_nonblock(playerc_client_t *client);
00742
00743
00744 int playerc_client_read_nonblock_withproxy(playerc_client_t *client, void ** proxy);
00745
00752 void playerc_client_set_request_timeout(playerc_client_t* client, uint32_t seconds);
00753
00760 void playerc_client_set_retry_limit(playerc_client_t* client, int limit);
00761
00767 void playerc_client_set_retry_time(playerc_client_t* client, double time);
00768
00771 int playerc_client_write(playerc_client_t *client,
00772 struct _playerc_device_t *device,
00773 uint8_t subtype,
00774 void *cmd, double* timestamp);
00775
00776
00778
00779
00780
00781
00794 typedef struct _playerc_device_t
00795 {
00799 void *id;
00800
00802 playerc_client_t *client;
00803
00805 player_devaddr_t addr;
00806
00808 char drivername[PLAYER_MAX_DRIVER_STRING_LEN];
00809
00812 int subscribed;
00813
00815 double datatime;
00816
00818 double lasttime;
00819
00823 int fresh;
00827 int freshgeom;
00831 int freshconfig;
00832
00834 playerc_putmsg_fn_t putmsg;
00835
00837 void *user_data;
00838
00840 int callback_count;
00841 playerc_callback_fn_t callback[4];
00842 void *callback_data[4];
00843
00844 } playerc_device_t;
00845
00846
00848 void playerc_device_init(playerc_device_t *device, playerc_client_t *client,
00849 int code, int index, playerc_putmsg_fn_t putmsg);
00850
00852 void playerc_device_term(playerc_device_t *device);
00853
00855 int playerc_device_subscribe(playerc_device_t *device, int access);
00856
00858 int playerc_device_unsubscribe(playerc_device_t *device);
00859
00861 int playerc_device_hascapability(playerc_device_t *device, uint32_t type, uint32_t subtype);
00862
00864 int playerc_device_get_intprop(playerc_device_t *device, char *property, int32_t *value);
00865
00867 int playerc_device_set_intprop(playerc_device_t *device, char *property, int32_t value);
00868
00870 int playerc_device_get_dblprop(playerc_device_t *device, char *property, double *value);
00871
00873 int playerc_device_set_dblprop(playerc_device_t *device, char *property, double value);
00874
00876 int playerc_device_get_strprop(playerc_device_t *device, char *property, char **value);
00877
00879 int playerc_device_set_strprop(playerc_device_t *device, char *property, char *value);
00880
00881
00883
00884
00885
00886
00891
00892
00893
00903 typedef struct
00904 {
00906 playerc_device_t info;
00907
00909 uint8_t voltages_count;
00910
00912 float *voltages;
00913
00914 } playerc_aio_t;
00915
00916
00918 playerc_aio_t *playerc_aio_create(playerc_client_t *client, int index);
00919
00921 void playerc_aio_destroy(playerc_aio_t *device);
00922
00924 int playerc_aio_subscribe(playerc_aio_t *device, int access);
00925
00927 int playerc_aio_unsubscribe(playerc_aio_t *device);
00928
00930 int playerc_aio_set_output(playerc_aio_t *device, uint8_t id, float volt);
00931
00933 float playerc_aio_get_data(playerc_aio_t *device, uint32_t index);
00934
00936
00937
00938
00939
00950 #define PLAYERC_ACTARRAY_NUM_ACTUATORS PLAYER_ACTARRAY_NUM_ACTUATORS
00951 #define PLAYERC_ACTARRAY_ACTSTATE_IDLE PLAYER_ACTARRAY_ACTSTATE_IDLE
00952 #define PLAYERC_ACTARRAY_ACTSTATE_MOVING PLAYER_ACTARRAY_ACTSTATE_MOVING
00953 #define PLAYERC_ACTARRAY_ACTSTATE_BRAKED PLAYER_ACTARRAY_ACTSTATE_BRAKED
00954 #define PLAYERC_ACTARRAY_ACTSTATE_STALLED PLAYER_ACTARRAY_ACTSTATE_STALLED
00955 #define PLAYERC_ACTARRAY_TYPE_LINEAR PLAYER_ACTARRAY_TYPE_LINEAR
00956 #define PLAYERC_ACTARRAY_TYPE_ROTARY PLAYER_ACTARRAY_TYPE_ROTARY
00957
00958
00960 typedef struct
00961 {
00963 playerc_device_t info;
00964
00966 uint32_t actuators_count;
00968 player_actarray_actuator_t *actuators_data;
00970 uint32_t actuators_geom_count;
00971 player_actarray_actuatorgeom_t *actuators_geom;
00973 uint8_t motor_state;
00975 player_point_3d_t base_pos;
00977 player_orientation_3d_t base_orientation;
00978 } playerc_actarray_t;
00979
00981 playerc_actarray_t *playerc_actarray_create(playerc_client_t *client, int index);
00982
00984 void playerc_actarray_destroy(playerc_actarray_t *device);
00985
00987 int playerc_actarray_subscribe(playerc_actarray_t *device, int access);
00988
00990 int playerc_actarray_unsubscribe(playerc_actarray_t *device);
00991
00993 player_actarray_actuator_t playerc_actarray_get_actuator_data(playerc_actarray_t *device, int index);
00994
00996 player_actarray_actuatorgeom_t playerc_actarray_get_actuator_geom(playerc_actarray_t *device, int index);
00997
01000 int playerc_actarray_get_geom(playerc_actarray_t *device);
01001
01003 int playerc_actarray_position_cmd(playerc_actarray_t *device, int joint, float position);
01004
01006 int playerc_actarray_multi_position_cmd(playerc_actarray_t *device, float *positions, int positions_count);
01007
01009 int playerc_actarray_speed_cmd(playerc_actarray_t *device, int joint, float speed);
01010
01012 int playerc_actarray_multi_speed_cmd(playerc_actarray_t *device, float *speeds, int speeds_count);
01013
01015 int playerc_actarray_home_cmd(playerc_actarray_t *device, int joint);
01016
01018 int playerc_actarray_current_cmd(playerc_actarray_t *device, int joint, float current);
01019
01021 int playerc_actarray_multi_current_cmd(playerc_actarray_t *device, float *currents, int currents_count);
01022
01023
01027 int playerc_actarray_power(playerc_actarray_t *device, uint8_t enable);
01028
01030 int playerc_actarray_brakes(playerc_actarray_t *device, uint8_t enable);
01031
01033 int playerc_actarray_speed_config(playerc_actarray_t *device, int joint, float speed);
01034
01035
01036 int playerc_actarray_accel_config(playerc_actarray_t *device, int joint, float accel);
01037
01038
01040
01041
01042
01054 typedef struct
01055 {
01057 playerc_device_t info;
01058
01060 player_audio_mixer_channel_list_detail_t channel_details_list;
01061
01063 player_audio_wav_t wav_data;
01064
01066 player_audio_seq_t seq_data;
01067
01069 player_audio_mixer_channel_list_t mixer_data;
01070
01072 uint32_t state;
01073
01074 int last_index;
01075
01076 } playerc_audio_t;
01077
01079 playerc_audio_t *playerc_audio_create(playerc_client_t *client, int index);
01080
01082 void playerc_audio_destroy(playerc_audio_t *device);
01083
01085 int playerc_audio_subscribe(playerc_audio_t *device, int access);
01086
01088 int playerc_audio_unsubscribe(playerc_audio_t *device);
01089
01091 int playerc_audio_wav_play_cmd(playerc_audio_t *device, uint32_t data_count, uint8_t data[], uint32_t format);
01092
01094 int playerc_audio_wav_stream_rec_cmd(playerc_audio_t *device, uint8_t state);
01095
01097 int playerc_audio_sample_play_cmd(playerc_audio_t *device, int index);
01098
01100 int playerc_audio_seq_play_cmd(playerc_audio_t *device, player_audio_seq_t * tones);
01101
01103 int playerc_audio_mixer_multchannels_cmd(playerc_audio_t *device, player_audio_mixer_channel_list_t * levels);
01104
01106 int playerc_audio_mixer_channel_cmd(playerc_audio_t *device, uint32_t index, float amplitude, uint8_t active);
01107
01110 int playerc_audio_wav_rec(playerc_audio_t *device);
01111
01113 int playerc_audio_sample_load(playerc_audio_t *device, int index, uint32_t data_count, uint8_t data[], uint32_t format);
01114
01117 int playerc_audio_sample_retrieve(playerc_audio_t *device, int index);
01118
01120 int playerc_audio_sample_rec(playerc_audio_t *device, int index, uint32_t length);
01121
01124 int playerc_audio_get_mixer_levels(playerc_audio_t *device);
01125
01128 int playerc_audio_get_mixer_details(playerc_audio_t *device);
01129
01131
01132
01142 #define PLAYERC_BLACKBOARD_DATA_TYPE_NONE 0
01143 #define PLAYERC_BLACKBOARD_DATA_TYPE_SIMPLE 1
01144 #define PLAYERC_BLACKBOARD_DATA_TYPE_COMPLEX 2
01145
01146 #define PLAYERC_BLACKBOARD_DATA_SUBTYPE_NONE 0
01147 #define PLAYERC_BLACKBOARD_DATA_SUBTYPE_STRING 1
01148 #define PLAYERC_BLACKBOARD_DATA_SUBTYPE_INT 2
01149 #define PLAYERC_BLACKBOARD_DATA_SUBTYPE_DOUBLE 3
01150
01152 typedef struct playerc_blackboard
01153 {
01155 playerc_device_t info;
01157 void (*on_blackboard_event)(struct playerc_blackboard*, player_blackboard_entry_t);
01159 void *py_private;
01160 } playerc_blackboard_t;
01161
01163 playerc_blackboard_t *playerc_blackboard_create(playerc_client_t *client, int index);
01164
01166 void playerc_blackboard_destroy(playerc_blackboard_t *device);
01167
01169 int playerc_blackboard_subscribe(playerc_blackboard_t *device, int access);
01170
01172 int playerc_blackboard_unsubscribe(playerc_blackboard_t *device);
01173
01176 int playerc_blackboard_subscribe_to_key(playerc_blackboard_t *device, const char* key, const char* group, player_blackboard_entry_t** entry);
01177
01180 int playerc_blackboard_get_entry(playerc_blackboard_t *device, const char* key, const char* group, player_blackboard_entry_t** entry);
01181
01183 int playerc_blackboard_unsubscribe_from_key(playerc_blackboard_t *device, const char* key, const char* group);
01184
01186 int playerc_blackboard_subscribe_to_group(playerc_blackboard_t *device, const char* group);
01187
01189 int playerc_blackboard_unsubscribe_from_group(playerc_blackboard_t *device, const char* group);
01190
01192 int playerc_blackboard_set_entry(playerc_blackboard_t *device, player_blackboard_entry_t* entry);
01193
01194 int playerc_blackboard_set_string(playerc_blackboard_t *device, const char* key, const char* group, const char* value);
01195
01196 int playerc_blackboard_set_int(playerc_blackboard_t *device, const char* key, const char* group, const int value);
01197
01198 int playerc_blackboard_set_double(playerc_blackboard_t *device, const char* key, const char* group, const double value);
01199
01202
01213 typedef struct
01214 {
01216 playerc_device_t info;
01217
01218 uint32_t enabled;
01219 double duty_cycle;
01220 double period;
01221 uint8_t red, green, blue;
01222 } playerc_blinkenlight_t;
01223
01224
01226 playerc_blinkenlight_t *playerc_blinkenlight_create(playerc_client_t *client, int index);
01227
01229 void playerc_blinkenlight_destroy(playerc_blinkenlight_t *device);
01230
01232 int playerc_blinkenlight_subscribe(playerc_blinkenlight_t *device, int access);
01233
01235 int playerc_blinkenlight_unsubscribe(playerc_blinkenlight_t *device);
01236
01238 int playerc_blinkenlight_enable( playerc_blinkenlight_t *device,
01239 uint32_t enable );
01240
01242 int playerc_blinkenlight_color( playerc_blinkenlight_t *device,
01243 uint32_t id,
01244 uint8_t red,
01245 uint8_t green,
01246 uint8_t blue );
01249 int playerc_blinkenlight_blink( playerc_blinkenlight_t *device,
01250 uint32_t id,
01251 float period,
01252 float duty_cycle );
01255
01266 typedef player_blobfinder_blob_t playerc_blobfinder_blob_t;
01267
01269 typedef struct
01270 {
01272 playerc_device_t info;
01273
01275 unsigned int width, height;
01276
01278 unsigned int blobs_count;
01279 playerc_blobfinder_blob_t *blobs;
01280
01281 } playerc_blobfinder_t;
01282
01283
01285 playerc_blobfinder_t *playerc_blobfinder_create(playerc_client_t *client, int index);
01286
01288 void playerc_blobfinder_destroy(playerc_blobfinder_t *device);
01289
01291 int playerc_blobfinder_subscribe(playerc_blobfinder_t *device, int access);
01292
01294 int playerc_blobfinder_unsubscribe(playerc_blobfinder_t *device);
01295
01296
01298
01299
01300
01301
01312 typedef struct
01313 {
01315 playerc_device_t info;
01316
01318 int pose_count;
01319
01323 player_bumper_define_t *poses;
01324
01326 int bumper_count;
01327
01329 uint8_t *bumpers;
01330
01331 } playerc_bumper_t;
01332
01333
01335 playerc_bumper_t *playerc_bumper_create(playerc_client_t *client, int index);
01336
01338 void playerc_bumper_destroy(playerc_bumper_t *device);
01339
01341 int playerc_bumper_subscribe(playerc_bumper_t *device, int access);
01342
01344 int playerc_bumper_unsubscribe(playerc_bumper_t *device);
01345
01352 int playerc_bumper_get_geom(playerc_bumper_t *device);
01353
01354
01356
01357
01358
01359
01369 typedef struct
01370 {
01372 playerc_device_t info;
01373
01375 int width, height;
01376
01378 int bpp;
01379
01381 int format;
01382
01386 int fdiv;
01387
01389 int compression;
01390
01392 int image_count;
01393
01398 uint8_t *image;
01399
01400 } playerc_camera_t;
01401
01402
01404 playerc_camera_t *playerc_camera_create(playerc_client_t *client, int index);
01405
01407 void playerc_camera_destroy(playerc_camera_t *device);
01408
01410 int playerc_camera_subscribe(playerc_camera_t *device, int access);
01411
01413 int playerc_camera_unsubscribe(playerc_camera_t *device);
01414
01416 void playerc_camera_decompress(playerc_camera_t *device);
01417
01419 void playerc_camera_save(playerc_camera_t *device, const char *filename);
01420
01422
01423
01424
01425
01435 typedef struct
01436 {
01438 playerc_device_t info;
01439
01441 uint8_t count;
01442
01444 uint32_t digin;
01445
01446 } playerc_dio_t;
01447
01448
01450 playerc_dio_t *playerc_dio_create(playerc_client_t *client, int index);
01451
01453 void playerc_dio_destroy(playerc_dio_t *device);
01454
01456 int playerc_dio_subscribe(playerc_dio_t *device, int access);
01457
01459 int playerc_dio_unsubscribe(playerc_dio_t *device);
01460
01462 int playerc_dio_set_output(playerc_dio_t *device, uint8_t output_count, uint32_t digout);
01463
01464
01466
01467
01468
01469
01484 typedef struct
01485 {
01487 playerc_device_t info;
01488
01493 player_fiducial_geom_t fiducial_geom;
01494
01496 int fiducials_count;
01497 player_fiducial_item_t *fiducials;
01498
01499 } playerc_fiducial_t;
01500
01501
01503 playerc_fiducial_t *playerc_fiducial_create(playerc_client_t *client, int index);
01504
01506 void playerc_fiducial_destroy(playerc_fiducial_t *device);
01507
01509 int playerc_fiducial_subscribe(playerc_fiducial_t *device, int access);
01510
01512 int playerc_fiducial_unsubscribe(playerc_fiducial_t *device);
01513
01520 int playerc_fiducial_get_geom(playerc_fiducial_t *device);
01521
01522
01524
01525
01526
01535 typedef struct
01536 {
01538 playerc_device_t info;
01539
01541 double utc_time;
01542
01546 double lat, lon;
01547
01550 double alt;
01551
01553 double utm_e, utm_n;
01554
01556 double hdop;
01557
01559 double vdop;
01560
01562 double err_horz, err_vert;
01563
01565 int quality;
01566
01568 int sat_count;
01569
01570 } playerc_gps_t;
01571
01572
01574 playerc_gps_t *playerc_gps_create(playerc_client_t *client, int index);
01575
01577 void playerc_gps_destroy(playerc_gps_t *device);
01578
01580 int playerc_gps_subscribe(playerc_gps_t *device, int access);
01581
01583 int playerc_gps_unsubscribe(playerc_gps_t *device);
01584
01585
01587
01588
01589
01599 typedef struct
01600 {
01602 playerc_device_t info;
01603
01605 player_color_t color;
01606
01607 } playerc_graphics2d_t;
01608
01609
01611 playerc_graphics2d_t *playerc_graphics2d_create(playerc_client_t *client, int index);
01612
01614 void playerc_graphics2d_destroy(playerc_graphics2d_t *device);
01615
01617 int playerc_graphics2d_subscribe(playerc_graphics2d_t *device, int access);
01618
01620 int playerc_graphics2d_unsubscribe(playerc_graphics2d_t *device);
01621
01623 int playerc_graphics2d_setcolor(playerc_graphics2d_t *device,
01624 player_color_t col );
01625
01627 int playerc_graphics2d_draw_points(playerc_graphics2d_t *device,
01628 player_point_2d_t pts[],
01629 int count );
01630
01632 int playerc_graphics2d_draw_polyline(playerc_graphics2d_t *device,
01633 player_point_2d_t pts[],
01634 int count );
01635
01637 int playerc_graphics2d_draw_polygon(playerc_graphics2d_t *device,
01638 player_point_2d_t pts[],
01639 int count,
01640 int filled,
01641 player_color_t fill_color );
01642
01644 int playerc_graphics2d_clear(playerc_graphics2d_t *device );
01645
01646
01649
01659 typedef struct
01660 {
01662 playerc_device_t info;
01663
01665 player_color_t color;
01666
01667 } playerc_graphics3d_t;
01668
01669
01671 playerc_graphics3d_t *playerc_graphics3d_create(playerc_client_t *client, int index);
01672
01674 void playerc_graphics3d_destroy(playerc_graphics3d_t *device);
01675
01677 int playerc_graphics3d_subscribe(playerc_graphics3d_t *device, int access);
01678
01680 int playerc_graphics3d_unsubscribe(playerc_graphics3d_t *device);
01681
01683 int playerc_graphics3d_setcolor(playerc_graphics3d_t *device,
01684 player_color_t col );
01685
01687 int playerc_graphics3d_draw(playerc_graphics3d_t *device,
01688 player_graphics3d_draw_mode_t mode,
01689 player_point_3d_t pts[],
01690 int count );
01691
01693 int playerc_graphics3d_clear(playerc_graphics3d_t *device );
01694
01696 int playerc_graphics3d_translate(playerc_graphics3d_t *device,
01697 double x, double y, double z );
01698
01699
01701 int playerc_graphics3d_rotate( playerc_graphics3d_t *device,
01702 double a, double x, double y, double z );
01705
01715 typedef struct
01716 {
01718 playerc_device_t info;
01719
01726 player_pose3d_t pose;
01727 player_bbox3d_t outer_size;
01728 player_bbox3d_t inner_size;
01730 uint8_t num_beams;
01732 uint8_t capacity;
01733
01737 uint8_t state;
01739 uint32_t beams;
01741 uint8_t stored;
01742 } playerc_gripper_t;
01743
01745 playerc_gripper_t *playerc_gripper_create(playerc_client_t *client, int index);
01746
01748 void playerc_gripper_destroy(playerc_gripper_t *device);
01749
01751 int playerc_gripper_subscribe(playerc_gripper_t *device, int access);
01752
01754 int playerc_gripper_unsubscribe(playerc_gripper_t *device);
01755
01757 int playerc_gripper_open_cmd(playerc_gripper_t *device);
01758
01760 int playerc_gripper_close_cmd(playerc_gripper_t *device);
01761
01763 int playerc_gripper_stop_cmd(playerc_gripper_t *device);
01764
01766 int playerc_gripper_store_cmd(playerc_gripper_t *device);
01767
01769 int playerc_gripper_retrieve_cmd(playerc_gripper_t *device);
01770
01773 void playerc_gripper_printout(playerc_gripper_t *device, const char* prefix);
01774
01779 int playerc_gripper_get_geom(playerc_gripper_t *device);
01780
01782
01783
01784
01798 typedef struct
01799 {
01801 playerc_device_t info;
01803 player_health_cpu_t cpu_usage;
01805 player_health_memory_t mem;
01807 player_health_memory_t swap;
01808 } playerc_health_t;
01809
01810
01812 playerc_health_t *playerc_health_create(playerc_client_t *client, int index);
01813
01815 void playerc_health_destroy(playerc_health_t *device);
01816
01818 int playerc_health_subscribe(playerc_health_t *device, int access);
01819
01821 int playerc_health_unsubscribe(playerc_health_t *device);
01822
01823
01825
01826
01827
01828
01839 typedef struct
01840 {
01842 playerc_device_t info;
01843
01844
01845 player_ir_data_t data;
01846
01847
01848 player_ir_pose_t poses;
01849
01850 } playerc_ir_t;
01851
01852
01854 playerc_ir_t *playerc_ir_create(playerc_client_t *client, int index);
01855
01857 void playerc_ir_destroy(playerc_ir_t *device);
01858
01860 int playerc_ir_subscribe(playerc_ir_t *device, int access);
01861
01863 int playerc_ir_unsubscribe(playerc_ir_t *device);
01864
01871 int playerc_ir_get_geom(playerc_ir_t *device);
01872
01873
01875
01876
01877
01878
01879
01893 typedef struct
01894 {
01896 playerc_device_t info;
01897
01901 double pose[3];
01902 double size[2];
01903
01905 double robot_pose[3];
01906
01908 int intensity_on;
01909
01911 int scan_count;
01912
01914 double scan_start;
01915
01917 double scan_res;
01918
01920 double range_res;
01921
01923 double max_range;
01924
01926 double scanning_frequency;
01927
01929 double *ranges;
01930
01932 double (*scan)[2];
01933
01935 player_point_2d_t *point;
01936
01940 int *intensity;
01941
01943 int scan_id;
01944
01946 int laser_id;
01947
01951 double min_right;
01952
01956 double min_left;
01957 } playerc_laser_t;
01958
01959
01961 playerc_laser_t *playerc_laser_create(playerc_client_t *client, int index);
01962
01964 void playerc_laser_destroy(playerc_laser_t *device);
01965
01967 int playerc_laser_subscribe(playerc_laser_t *device, int access);
01968
01970 int playerc_laser_unsubscribe(playerc_laser_t *device);
01971
01994 int playerc_laser_set_config(playerc_laser_t *device,
01995 double min_angle, double max_angle,
01996 double resolution,
01997 double range_res,
01998 unsigned char intensity,
01999 double scanning_frequency);
02000
02023 int playerc_laser_get_config(playerc_laser_t *device,
02024 double *min_angle,
02025 double *max_angle,
02026 double *resolution,
02027 double *range_res,
02028 unsigned char *intensity,
02029 double *scanning_frequency);
02030
02037 int playerc_laser_get_geom(playerc_laser_t *device);
02038
02043 int playerc_laser_get_id (playerc_laser_t *device);
02044
02047 void playerc_laser_printout( playerc_laser_t * device,
02048 const char* prefix );
02049
02051
02052
02053
02065 typedef struct
02066 {
02068 playerc_device_t info;
02069
02070 player_limb_data_t data;
02071 player_limb_geom_req_t geom;
02072 } playerc_limb_t;
02073
02075 playerc_limb_t *playerc_limb_create(playerc_client_t *client, int index);
02076
02078 void playerc_limb_destroy(playerc_limb_t *device);
02079
02081 int playerc_limb_subscribe(playerc_limb_t *device, int access);
02082
02084 int playerc_limb_unsubscribe(playerc_limb_t *device);
02085
02088 int playerc_limb_get_geom(playerc_limb_t *device);
02089
02091 int playerc_limb_home_cmd(playerc_limb_t *device);
02092
02094 int playerc_limb_stop_cmd(playerc_limb_t *device);
02095
02097 int playerc_limb_setpose_cmd(playerc_limb_t *device, float pX, float pY, float pZ, float aX, float aY, float aZ, float oX, float oY, float oZ);
02098
02101 int playerc_limb_setposition_cmd(playerc_limb_t *device, float pX, float pY, float pZ);
02102
02105 int playerc_limb_vecmove_cmd(playerc_limb_t *device, float x, float y, float z, float length);
02106
02110 int playerc_limb_power(playerc_limb_t *device, uint32_t enable);
02111
02113 int playerc_limb_brakes(playerc_limb_t *device, uint32_t enable);
02114
02116 int playerc_limb_speed_config(playerc_limb_t *device, float speed);
02117
02119
02120
02121
02122
02139 typedef struct playerc_localize_particle
02140 {
02141 double pose[3];
02142 double weight;
02143 } playerc_localize_particle_t;
02144
02145
02147 typedef struct
02148 {
02150 playerc_device_t info;
02151
02153 int map_size_x, map_size_y;
02154
02156 double map_scale;
02157
02159 int map_tile_x, map_tile_y;
02160
02162 int8_t *map_cells;
02163
02165 int pending_count;
02166
02168 double pending_time;
02169
02171 int hypoth_count;
02172 player_localize_hypoth_t *hypoths;
02173
02174 double mean[3];
02175 double variance;
02176 int num_particles;
02177 playerc_localize_particle_t *particles;
02178
02179 } playerc_localize_t;
02180
02181
02183 playerc_localize_t *playerc_localize_create(playerc_client_t *client, int index);
02184
02186 void playerc_localize_destroy(playerc_localize_t *device);
02187
02189 int playerc_localize_subscribe(playerc_localize_t *device, int access);
02190
02192 int playerc_localize_unsubscribe(playerc_localize_t *device);
02193
02195 int playerc_localize_set_pose(playerc_localize_t *device, double pose[3], double cov[3]);
02196
02199 int playerc_localize_get_particles(playerc_localize_t *device);
02200
02202
02203
02204
02205
02215 typedef struct
02216 {
02218 playerc_device_t info;
02219
02222 int type;
02223
02226 int state;
02227 } playerc_log_t;
02228
02229
02231 playerc_log_t *playerc_log_create(playerc_client_t *client, int index);
02232
02234 void playerc_log_destroy(playerc_log_t *device);
02235
02237 int playerc_log_subscribe(playerc_log_t *device, int access);
02238
02240 int playerc_log_unsubscribe(playerc_log_t *device);
02241
02243 int playerc_log_set_write_state(playerc_log_t* device, int state);
02244
02246 int playerc_log_set_read_state(playerc_log_t* device, int state);
02247
02249 int playerc_log_set_read_rewind(playerc_log_t* device);
02250
02256 int playerc_log_get_state(playerc_log_t* device);
02257
02259 int playerc_log_set_filename(playerc_log_t* device, const char* fname);
02260
02261
02265
02275 typedef struct
02276 {
02278 playerc_device_t info;
02279
02281 double resolution;
02282
02284 int width, height;
02285
02287 double origin[2];
02288
02290 char* cells;
02291
02294 double vminx, vminy, vmaxx, vmaxy;
02295 int num_segments;
02296 player_segment_t* segments;
02297 } playerc_map_t;
02298
02301 #define PLAYERC_MAP_INDEX(dev, i, j) ((dev->width) * (j) + (i))
02302
02304 playerc_map_t *playerc_map_create(playerc_client_t *client, int index);
02305
02307 void playerc_map_destroy(playerc_map_t *device);
02308
02310 int playerc_map_subscribe(playerc_map_t *device, int access);
02311
02313 int playerc_map_unsubscribe(playerc_map_t *device);
02314
02316 int playerc_map_get_map(playerc_map_t* device);
02317
02319 int playerc_map_get_vector(playerc_map_t* device);
02320
02322
02323
02332 typedef struct
02333 {
02335 playerc_device_t info;
02337 uint32_t srid;
02339 player_extent2d_t extent;
02341 uint32_t layers_count;
02343 player_vectormap_layer_data_t** layers_data;
02345 player_vectormap_layer_info_t** layers_info;
02347 GEOSGeom geom;
02348
02349 } playerc_vectormap_t;
02350
02352 playerc_vectormap_t *playerc_vectormap_create(playerc_client_t *client, int index);
02353
02355 void playerc_vectormap_destroy(playerc_vectormap_t *device);
02356
02358 int playerc_vectormap_subscribe(playerc_vectormap_t *device, int access);
02359
02361 int playerc_vectormap_unsubscribe(playerc_vectormap_t *device);
02362
02364 int playerc_vectormap_get_map_info(playerc_vectormap_t* device);
02365
02367 int playerc_vectormap_get_layer_data(playerc_vectormap_t *device, unsigned layer_index);
02368
02370 int playerc_vectormap_write_layer(playerc_vectormap_t *device, const player_vectormap_layer_data_t * data);
02371
02373 void playerc_vectormap_cleanup(playerc_vectormap_t *device);
02374
02377 GEOSGeom playerc_vectormap_get_feature_data(playerc_vectormap_t *device, unsigned layer_index, unsigned feature_index);
02378
02381
02392 typedef struct
02393 {
02395 playerc_device_t info;
02396
02398 int data_count;
02399
02401 uint8_t *data;
02402 } playerc_opaque_t;
02403
02405 playerc_opaque_t *playerc_opaque_create(playerc_client_t *client, int index);
02406
02408 void playerc_opaque_destroy(playerc_opaque_t *device);
02409
02411 int playerc_opaque_subscribe(playerc_opaque_t *device, int access);
02412
02414 int playerc_opaque_unsubscribe(playerc_opaque_t *device);
02415
02417 int playerc_opaque_cmd(playerc_opaque_t *device, player_opaque_data_t *data);
02418
02425 int playerc_opaque_req(playerc_opaque_t *device, player_opaque_data_t *request, player_opaque_data_t **reply);
02426
02428
02429
02430
02431
02441 typedef struct
02442 {
02444 playerc_device_t info;
02445
02447 int path_valid;
02448
02450 int path_done;
02451
02453 double px, py, pa;
02454
02456 double gx, gy, ga;
02457
02459 double wx, wy, wa;
02460
02464 int curr_waypoint;
02465
02467 int waypoint_count;
02468
02471 double (*waypoints)[3];
02472
02473 } playerc_planner_t;
02474
02476 playerc_planner_t *playerc_planner_create(playerc_client_t *client, int index);
02477
02479 void playerc_planner_destroy(playerc_planner_t *device);
02480
02482 int playerc_planner_subscribe(playerc_planner_t *device, int access);
02483
02485 int playerc_planner_unsubscribe(playerc_planner_t *device);
02486
02488 int playerc_planner_set_cmd_pose(playerc_planner_t *device,
02489 double gx, double gy, double ga);
02490
02497 int playerc_planner_get_waypoints(playerc_planner_t *device);
02498
02504 int playerc_planner_enable(playerc_planner_t *device, int state);
02505
02507
02508
02509
02520 typedef struct
02521 {
02523 playerc_device_t info;
02524
02528 double pose[3];
02529 double size[2];
02530
02532 double pos;
02533
02535 double vel;
02536
02538 int stall;
02539
02551 int status;
02552
02553 } playerc_position1d_t;
02554
02556 playerc_position1d_t *playerc_position1d_create(playerc_client_t *client,
02557 int index);
02558
02560 void playerc_position1d_destroy(playerc_position1d_t *device);
02561
02563 int playerc_position1d_subscribe(playerc_position1d_t *device, int access);
02564
02566 int playerc_position1d_unsubscribe(playerc_position1d_t *device);
02567
02569 int playerc_position1d_enable(playerc_position1d_t *device, int enable);
02570
02573 int playerc_position1d_get_geom(playerc_position1d_t *device);
02574
02576 int playerc_position1d_set_cmd_vel(playerc_position1d_t *device,
02577 double vel, int state);
02578
02582 int playerc_position1d_set_cmd_pos(playerc_position1d_t *device,
02583 double pos, int state);
02584
02589 int playerc_position1d_set_cmd_pos_with_vel(playerc_position1d_t *device,
02590 double pos, double vel, int state);
02591
02593 int playerc_position1d_set_odom(playerc_position1d_t *device,
02594 double odom);
02595
02597
02598
02599
02600
02614 typedef struct
02615 {
02617 playerc_device_t info;
02618
02622 double pose[3];
02623 double size[2];
02624
02626 double px, py, pa;
02627
02629 double vx, vy, va;
02630
02632 int stall;
02633
02634 } playerc_position2d_t;
02635
02637 playerc_position2d_t *playerc_position2d_create(playerc_client_t *client,
02638 int index);
02639
02641 void playerc_position2d_destroy(playerc_position2d_t *device);
02642
02644 int playerc_position2d_subscribe(playerc_position2d_t *device, int access);
02645
02647 int playerc_position2d_unsubscribe(playerc_position2d_t *device);
02648
02650 int playerc_position2d_enable(playerc_position2d_t *device, int enable);
02651
02654 int playerc_position2d_get_geom(playerc_position2d_t *device);
02655
02660 int playerc_position2d_set_cmd_vel(playerc_position2d_t *device,
02661 double vx, double vy, double va, int state);
02662
02664 int playerc_position2d_set_cmd_pose_with_vel(playerc_position2d_t *device,
02665 player_pose2d_t pos,
02666 player_pose2d_t vel,
02667 int state);
02668
02671 int playerc_position2d_set_cmd_pose(playerc_position2d_t *device,
02672 double gx, double gy, double ga, int state);
02673
02675 int playerc_position2d_set_cmd_car(playerc_position2d_t *device,
02676 double vx, double a);
02677
02679 int playerc_position2d_set_odom(playerc_position2d_t *device,
02680 double ox, double oy, double oa);
02681
02683
02684
02685
02700 typedef struct
02701 {
02703 playerc_device_t info;
02704
02708 double pose[3];
02709 double size[2];
02710
02712 double pos_x, pos_y, pos_z;
02713
02715 double pos_roll, pos_pitch, pos_yaw;
02716
02718 double vel_x, vel_y, vel_z;
02719
02721 double vel_roll, vel_pitch, vel_yaw;
02722
02724 int stall;
02725
02726 } playerc_position3d_t;
02727
02728
02730 playerc_position3d_t *playerc_position3d_create(playerc_client_t *client,
02731 int index);
02732
02734 void playerc_position3d_destroy(playerc_position3d_t *device);
02735
02737 int playerc_position3d_subscribe(playerc_position3d_t *device, int access);
02738
02740 int playerc_position3d_unsubscribe(playerc_position3d_t *device);
02741
02743 int playerc_position3d_enable(playerc_position3d_t *device, int enable);
02744
02747 int playerc_position3d_get_geom(playerc_position3d_t *device);
02748
02753 int playerc_position3d_set_velocity(playerc_position3d_t *device,
02754 double vx, double vy, double vz,
02755 double vr, double vp, double vt,
02756 int state);
02757
02759 int playerc_position3d_set_speed(playerc_position3d_t *device,
02760 double vx, double vy, double vz, int state);
02761
02764 int playerc_position3d_set_pose(playerc_position3d_t *device,
02765 double gx, double gy, double gz,
02766 double gr, double gp, double gt);
02767
02768
02770 int playerc_position3d_set_pose_with_vel(playerc_position3d_t *device,
02771 player_pose3d_t pos,
02772 player_pose3d_t vel);
02773
02775 int playerc_position3d_set_cmd_pose(playerc_position3d_t *device,
02776 double gx, double gy, double gz);
02777
02779 int playerc_position3d_set_vel_mode(playerc_position3d_t *device, int mode);
02780
02782 int playerc_position3d_set_odom(playerc_position3d_t *device,
02783 double ox, double oy, double oz,
02784 double oroll, double opitch, double oyaw);
02785
02787 int playerc_position3d_reset_odom(playerc_position3d_t *device);
02788
02790
02791
02792
02793
02804 typedef struct
02805 {
02807 playerc_device_t info;
02808
02811 int valid;
02812
02814 double charge;
02815
02817 double percent;
02818
02820 double joules;
02821
02824 double watts;
02825
02827 int charging;
02828
02829 } playerc_power_t;
02830
02831
02833 playerc_power_t *playerc_power_create(playerc_client_t *client, int index);
02834
02836 void playerc_power_destroy(playerc_power_t *device);
02837
02839 int playerc_power_subscribe(playerc_power_t *device, int access);
02840
02842 int playerc_power_unsubscribe(playerc_power_t *device);
02843
02844
02846
02847
02848
02849
02850
02861 typedef struct
02862 {
02864 playerc_device_t info;
02865
02869 double pan, tilt;
02870
02872 double zoom;
02873
02875 int status;
02876 } playerc_ptz_t;
02877
02878
02880 playerc_ptz_t *playerc_ptz_create(playerc_client_t *client, int index);
02881
02883 void playerc_ptz_destroy(playerc_ptz_t *device);
02884
02886 int playerc_ptz_subscribe(playerc_ptz_t *device, int access);
02887
02889 int playerc_ptz_unsubscribe(playerc_ptz_t *device);
02890
02899 int playerc_ptz_set(playerc_ptz_t *device, double pan, double tilt, double zoom);
02900
02906 int playerc_ptz_query_status(playerc_ptz_t *device);
02907
02918 int playerc_ptz_set_ws(playerc_ptz_t *device, double pan, double tilt, double zoom,
02919 double panspeed, double tiltspeed);
02920
02928 int playerc_ptz_set_control_mode(playerc_ptz_t *device, int mode);
02929
02931
02932
02933
02943 typedef struct
02944 {
02946 playerc_device_t info;
02947
02949 uint32_t sensor_count;
02950
02952 double min_angle;
02954 double max_angle;
02956 double resolution;
02958 double max_range;
02960 double range_res;
02962 double frequency;
02963
02967 player_pose3d_t device_pose;
02968 player_bbox3d_t device_size;
02972 player_pose3d_t *sensor_poses;
02973 player_bbox3d_t *sensor_sizes;
02974
02976 uint32_t ranges_count;
02978 double *ranges;
02979
02981 uint32_t intensities_count;
02985 double *intensities;
02986
02988 uint32_t bearings_count;
02990 double *bearings;
02991
02993 uint32_t points_count;
02995 player_point_3d_t *points;
02996
02997 } playerc_ranger_t;
02998
03000 playerc_ranger_t *playerc_ranger_create(playerc_client_t *client, int index);
03001
03003 void playerc_ranger_destroy(playerc_ranger_t *device);
03004
03006 int playerc_ranger_subscribe(playerc_ranger_t *device, int access);
03007
03009 int playerc_ranger_unsubscribe(playerc_ranger_t *device);
03010
03015 int playerc_ranger_get_geom(playerc_ranger_t *device);
03016
03020 int playerc_ranger_power_config(playerc_ranger_t *device, uint8_t value);
03021
03025 int playerc_ranger_intns_config(playerc_ranger_t *device, uint8_t value);
03026
03035 int playerc_ranger_set_config(playerc_ranger_t *device, double min_angle,
03036 double max_angle, double resolution,
03037 double max_range, double range_res,
03038 double frequency);
03039
03048 int playerc_ranger_get_config(playerc_ranger_t *device, double *min_angle,
03049 double *max_angle, double *resolution,
03050 double *max_range, double *range_res,
03051 double *frequency);
03052
03054
03055
03056
03067 typedef struct
03068 {
03070 playerc_device_t info;
03071
03073 int pose_count;
03074
03077 player_pose3d_t *poses;
03078
03080 int scan_count;
03081
03083 double *scan;
03084
03085 } playerc_sonar_t;
03086
03087
03089 playerc_sonar_t *playerc_sonar_create(playerc_client_t *client, int index);
03090
03092 void playerc_sonar_destroy(playerc_sonar_t *device);
03093
03095 int playerc_sonar_subscribe(playerc_sonar_t *device, int access);
03096
03098 int playerc_sonar_unsubscribe(playerc_sonar_t *device);
03099
03105 int playerc_sonar_get_geom(playerc_sonar_t *device);
03106
03108
03109
03110
03122 typedef struct
03123 {
03125 uint8_t mac[32];
03126
03128 uint8_t ip[32];
03129
03131 uint8_t essid[32];
03132
03134 int mode;
03135
03137 int encrypt;
03138
03140 double freq;
03141
03143 int qual, level, noise;
03144
03145 } playerc_wifi_link_t;
03146
03147
03149 typedef struct
03150 {
03152 playerc_device_t info;
03153
03155 playerc_wifi_link_t *links;
03156 int link_count;
03157 char ip[32];
03158 } playerc_wifi_t;
03159
03160
03162 playerc_wifi_t *playerc_wifi_create(playerc_client_t *client, int index);
03163
03165 void playerc_wifi_destroy(playerc_wifi_t *device);
03166
03168 int playerc_wifi_subscribe(playerc_wifi_t *device, int access);
03169
03171 int playerc_wifi_unsubscribe(playerc_wifi_t *device);
03172
03174 playerc_wifi_link_t *playerc_wifi_get_link(playerc_wifi_t *device, int link);
03175
03176
03178
03179
03180
03192 typedef struct
03193 {
03195 playerc_device_t info;
03196
03197 } playerc_simulation_t;
03198
03199
03201 playerc_simulation_t *playerc_simulation_create(playerc_client_t *client, int index);
03202
03204 void playerc_simulation_destroy(playerc_simulation_t *device);
03205
03207 int playerc_simulation_subscribe(playerc_simulation_t *device, int access);
03208
03210 int playerc_simulation_unsubscribe(playerc_simulation_t *device);
03211
03213 int playerc_simulation_set_pose2d(playerc_simulation_t *device, char* name,
03214 double gx, double gy, double ga);
03215
03217 int playerc_simulation_get_pose2d(playerc_simulation_t *device, char* identifier,
03218 double *x, double *y, double *a);
03219
03221 int playerc_simulation_set_pose3d(playerc_simulation_t *device, char* name,
03222 double gx, double gy, double gz,
03223 double groll, double gpitch, double gyaw);
03224
03226 int playerc_simulation_get_pose3d(playerc_simulation_t *device, char* identifier,
03227 double *x, double *y, double *z,
03228 double *roll, double *pitch, double *yaw, double *time);
03229
03231 int playerc_simulation_set_property(playerc_simulation_t *device,
03232 char* name,
03233 char* property,
03234 void* value,
03235 size_t value_len);
03236
03238 int playerc_simulation_get_property(playerc_simulation_t *device,
03239 char* name,
03240 char* property,
03241 void* value,
03242 size_t value_len);
03244
03245
03246
03247
03257 typedef struct
03258 {
03260 playerc_device_t info;
03261 } playerc_speech_t;
03262
03263
03265 playerc_speech_t *playerc_speech_create(playerc_client_t *client, int index);
03266
03268 void playerc_speech_destroy(playerc_speech_t *device);
03269
03271 int playerc_speech_subscribe(playerc_speech_t *device, int access);
03272
03274 int playerc_speech_unsubscribe(playerc_speech_t *device);
03275
03277 int playerc_speech_say (playerc_speech_t *device, char *);
03278
03279
03281
03282
03283
03293 typedef struct
03294 {
03296 playerc_device_t info;
03297
03298 char *rawText;
03299
03300
03301 char **words;
03302 int wordCount;
03303 } playerc_speechrecognition_t;
03304
03305
03307 playerc_speechrecognition_t *playerc_speechrecognition_create(playerc_client_t *client, int index);
03308
03310 void playerc_speechrecognition_destroy(playerc_speechrecognition_t *device);
03311
03313 int playerc_speechrecognition_subscribe(playerc_speechrecognition_t *device, int access);
03314
03316 int playerc_speechrecognition_unsubscribe(playerc_speechrecognition_t *device);
03317
03319
03320
03321
03331 typedef struct
03332 {
03334 uint32_t type;
03336 uint32_t guid_count;
03338 uint8_t *guid;
03339 } playerc_rfidtag_t;
03340
03342 typedef struct
03343 {
03345 playerc_device_t info;
03346
03348 uint16_t tags_count;
03349
03351 playerc_rfidtag_t *tags;
03352 } playerc_rfid_t;
03353
03354
03356 playerc_rfid_t *playerc_rfid_create(playerc_client_t *client, int index);
03357
03359 void playerc_rfid_destroy(playerc_rfid_t *device);
03360
03362 int playerc_rfid_subscribe(playerc_rfid_t *device, int access);
03363
03365 int playerc_rfid_unsubscribe(playerc_rfid_t *device);
03366
03368
03369
03370
03380 typedef player_pointcloud3d_element_t playerc_pointcloud3d_element_t;
03381
03383 typedef struct
03384 {
03386 playerc_device_t info;
03387
03389 uint16_t points_count;
03390
03392 playerc_pointcloud3d_element_t *points;
03393 } playerc_pointcloud3d_t;
03394
03395
03397 playerc_pointcloud3d_t *playerc_pointcloud3d_create (playerc_client_t *client, int index);
03398
03400 void playerc_pointcloud3d_destroy (playerc_pointcloud3d_t *device);
03401
03403 int playerc_pointcloud3d_subscribe (playerc_pointcloud3d_t *device, int access);
03404
03406 int playerc_pointcloud3d_unsubscribe (playerc_pointcloud3d_t *device);
03407
03409
03410
03411
03421 typedef struct
03422 {
03424 playerc_device_t info;
03425
03427 player_pose3d_t pose;
03428
03430 player_imu_data_calib_t calib_data;
03431
03433 float q0, q1, q2, q3;
03434 } playerc_imu_t;
03435
03437 playerc_imu_t *playerc_imu_create (playerc_client_t *client, int index);
03438
03440 void playerc_imu_destroy (playerc_imu_t *device);
03441
03443 int playerc_imu_subscribe (playerc_imu_t *device, int access);
03444
03446 int playerc_imu_unsubscribe (playerc_imu_t *device);
03447
03449 int playerc_imu_datatype (playerc_imu_t *device, int value);
03450
03452 int playerc_imu_reset_orientation (playerc_imu_t *device, int value);
03453
03455
03456
03457
03470 typedef struct
03471 {
03473 playerc_device_t info;
03474
03476 uint32_t node_type;
03478 uint32_t node_id;
03480 uint32_t node_parent_id;
03482 player_wsn_node_data_t data_packet;
03483 } playerc_wsn_t;
03484
03485
03487 playerc_wsn_t *playerc_wsn_create(playerc_client_t *client, int index);
03488
03490 void playerc_wsn_destroy(playerc_wsn_t *device);
03491
03493 int playerc_wsn_subscribe(playerc_wsn_t *device, int access);
03494
03496 int playerc_wsn_unsubscribe(playerc_wsn_t *device);
03497
03499 int playerc_wsn_set_devstate(playerc_wsn_t *device, int node_id,
03500 int group_id, int devnr, int state);
03501
03503 int playerc_wsn_power(playerc_wsn_t *device, int node_id, int group_id,
03504 int value);
03505
03507 int playerc_wsn_datatype(playerc_wsn_t *device, int value);
03508
03510 int playerc_wsn_datafreq(playerc_wsn_t *device, int node_id, int group_id,
03511 double frequency);
03512
03514
03515
03516 #ifdef __cplusplus
03517 }
03518 #endif
03519
03520 #endif