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
01179 int playerc_blackboard_unsubscribe_from_key(playerc_blackboard_t *device, const char* key, const char* group);
01180
01182 int playerc_blackboard_subscribe_to_group(playerc_blackboard_t *device, const char* group);
01183
01185 int playerc_blackboard_unsubscribe_from_group(playerc_blackboard_t *device, const char* group);
01186
01188 int playerc_blackboard_set_entry(playerc_blackboard_t *device, player_blackboard_entry_t* entry);
01189
01190 int playerc_blackboard_set_string(playerc_blackboard_t *device, const char* key, const char* group, const char* value);
01191
01192 int playerc_blackboard_set_int(playerc_blackboard_t *device, const char* key, const char* group, const int value);
01193
01194 int playerc_blackboard_set_double(playerc_blackboard_t *device, const char* key, const char* group, const double value);
01195
01198
01209 typedef struct
01210 {
01212 playerc_device_t info;
01213
01214 uint32_t enabled;
01215 double duty_cycle;
01216 double period;
01217 uint8_t red, green, blue;
01218 } playerc_blinkenlight_t;
01219
01220
01222 playerc_blinkenlight_t *playerc_blinkenlight_create(playerc_client_t *client, int index);
01223
01225 void playerc_blinkenlight_destroy(playerc_blinkenlight_t *device);
01226
01228 int playerc_blinkenlight_subscribe(playerc_blinkenlight_t *device, int access);
01229
01231 int playerc_blinkenlight_unsubscribe(playerc_blinkenlight_t *device);
01232
01234 int playerc_blinkenlight_enable( playerc_blinkenlight_t *device,
01235 uint32_t enable );
01236
01238 int playerc_blinkenlight_color( playerc_blinkenlight_t *device,
01239 uint32_t id,
01240 uint8_t red,
01241 uint8_t green,
01242 uint8_t blue );
01245 int playerc_blinkenlight_blink( playerc_blinkenlight_t *device,
01246 uint32_t id,
01247 float period,
01248 float duty_cycle );
01251
01262 typedef player_blobfinder_blob_t playerc_blobfinder_blob_t;
01263
01265 typedef struct
01266 {
01268 playerc_device_t info;
01269
01271 unsigned int width, height;
01272
01274 unsigned int blobs_count;
01275 playerc_blobfinder_blob_t *blobs;
01276
01277 } playerc_blobfinder_t;
01278
01279
01281 playerc_blobfinder_t *playerc_blobfinder_create(playerc_client_t *client, int index);
01282
01284 void playerc_blobfinder_destroy(playerc_blobfinder_t *device);
01285
01287 int playerc_blobfinder_subscribe(playerc_blobfinder_t *device, int access);
01288
01290 int playerc_blobfinder_unsubscribe(playerc_blobfinder_t *device);
01291
01292
01294
01295
01296
01297
01308 typedef struct
01309 {
01311 playerc_device_t info;
01312
01314 int pose_count;
01315
01319 player_bumper_define_t *poses;
01320
01322 int bumper_count;
01323
01325 uint8_t *bumpers;
01326
01327 } playerc_bumper_t;
01328
01329
01331 playerc_bumper_t *playerc_bumper_create(playerc_client_t *client, int index);
01332
01334 void playerc_bumper_destroy(playerc_bumper_t *device);
01335
01337 int playerc_bumper_subscribe(playerc_bumper_t *device, int access);
01338
01340 int playerc_bumper_unsubscribe(playerc_bumper_t *device);
01341
01348 int playerc_bumper_get_geom(playerc_bumper_t *device);
01349
01350
01352
01353
01354
01355
01365 typedef struct
01366 {
01368 playerc_device_t info;
01369
01371 int width, height;
01372
01374 int bpp;
01375
01377 int format;
01378
01382 int fdiv;
01383
01385 int compression;
01386
01388 int image_count;
01389
01394 uint8_t *image;
01395
01396 } playerc_camera_t;
01397
01398
01400 playerc_camera_t *playerc_camera_create(playerc_client_t *client, int index);
01401
01403 void playerc_camera_destroy(playerc_camera_t *device);
01404
01406 int playerc_camera_subscribe(playerc_camera_t *device, int access);
01407
01409 int playerc_camera_unsubscribe(playerc_camera_t *device);
01410
01412 void playerc_camera_decompress(playerc_camera_t *device);
01413
01415 void playerc_camera_save(playerc_camera_t *device, const char *filename);
01416
01418
01419
01420
01421
01431 typedef struct
01432 {
01434 playerc_device_t info;
01435
01437 uint8_t count;
01438
01440 uint32_t digin;
01441
01442 } playerc_dio_t;
01443
01444
01446 playerc_dio_t *playerc_dio_create(playerc_client_t *client, int index);
01447
01449 void playerc_dio_destroy(playerc_dio_t *device);
01450
01452 int playerc_dio_subscribe(playerc_dio_t *device, int access);
01453
01455 int playerc_dio_unsubscribe(playerc_dio_t *device);
01456
01458 int playerc_dio_set_output(playerc_dio_t *device, uint8_t output_count, uint32_t digout);
01459
01460
01462
01463
01464
01465
01480 typedef struct
01481 {
01483 playerc_device_t info;
01484
01489 player_fiducial_geom_t fiducial_geom;
01490
01492 int fiducials_count;
01493 player_fiducial_item_t *fiducials;
01494
01495 } playerc_fiducial_t;
01496
01497
01499 playerc_fiducial_t *playerc_fiducial_create(playerc_client_t *client, int index);
01500
01502 void playerc_fiducial_destroy(playerc_fiducial_t *device);
01503
01505 int playerc_fiducial_subscribe(playerc_fiducial_t *device, int access);
01506
01508 int playerc_fiducial_unsubscribe(playerc_fiducial_t *device);
01509
01516 int playerc_fiducial_get_geom(playerc_fiducial_t *device);
01517
01518
01520
01521
01522
01531 typedef struct
01532 {
01534 playerc_device_t info;
01535
01537 double utc_time;
01538
01542 double lat, lon;
01543
01546 double alt;
01547
01549 double utm_e, utm_n;
01550
01552 double hdop;
01553
01555 double vdop;
01556
01558 double err_horz, err_vert;
01559
01561 int quality;
01562
01564 int sat_count;
01565
01566 } playerc_gps_t;
01567
01568
01570 playerc_gps_t *playerc_gps_create(playerc_client_t *client, int index);
01571
01573 void playerc_gps_destroy(playerc_gps_t *device);
01574
01576 int playerc_gps_subscribe(playerc_gps_t *device, int access);
01577
01579 int playerc_gps_unsubscribe(playerc_gps_t *device);
01580
01581
01583
01584
01585
01595 typedef struct
01596 {
01598 playerc_device_t info;
01599
01601 player_color_t color;
01602
01603 } playerc_graphics2d_t;
01604
01605
01607 playerc_graphics2d_t *playerc_graphics2d_create(playerc_client_t *client, int index);
01608
01610 void playerc_graphics2d_destroy(playerc_graphics2d_t *device);
01611
01613 int playerc_graphics2d_subscribe(playerc_graphics2d_t *device, int access);
01614
01616 int playerc_graphics2d_unsubscribe(playerc_graphics2d_t *device);
01617
01619 int playerc_graphics2d_setcolor(playerc_graphics2d_t *device,
01620 player_color_t col );
01621
01623 int playerc_graphics2d_draw_points(playerc_graphics2d_t *device,
01624 player_point_2d_t pts[],
01625 int count );
01626
01628 int playerc_graphics2d_draw_polyline(playerc_graphics2d_t *device,
01629 player_point_2d_t pts[],
01630 int count );
01631
01633 int playerc_graphics2d_draw_polygon(playerc_graphics2d_t *device,
01634 player_point_2d_t pts[],
01635 int count,
01636 int filled,
01637 player_color_t fill_color );
01638
01640 int playerc_graphics2d_clear(playerc_graphics2d_t *device );
01641
01642
01645
01655 typedef struct
01656 {
01658 playerc_device_t info;
01659
01661 player_color_t color;
01662
01663 } playerc_graphics3d_t;
01664
01665
01667 playerc_graphics3d_t *playerc_graphics3d_create(playerc_client_t *client, int index);
01668
01670 void playerc_graphics3d_destroy(playerc_graphics3d_t *device);
01671
01673 int playerc_graphics3d_subscribe(playerc_graphics3d_t *device, int access);
01674
01676 int playerc_graphics3d_unsubscribe(playerc_graphics3d_t *device);
01677
01679 int playerc_graphics3d_setcolor(playerc_graphics3d_t *device,
01680 player_color_t col );
01681
01683 int playerc_graphics3d_draw(playerc_graphics3d_t *device,
01684 player_graphics3d_draw_mode_t mode,
01685 player_point_3d_t pts[],
01686 int count );
01687
01689 int playerc_graphics3d_clear(playerc_graphics3d_t *device );
01690
01692 int playerc_graphics3d_translate(playerc_graphics3d_t *device,
01693 double x, double y, double z );
01694
01695
01697 int playerc_graphics3d_rotate( playerc_graphics3d_t *device,
01698 double a, double x, double y, double z );
01701
01711 typedef struct
01712 {
01714 playerc_device_t info;
01715
01722 player_pose3d_t pose;
01723 player_bbox3d_t outer_size;
01724 player_bbox3d_t inner_size;
01726 uint8_t num_beams;
01728 uint8_t capacity;
01729
01733 uint8_t state;
01735 uint32_t beams;
01737 uint8_t stored;
01738 } playerc_gripper_t;
01739
01741 playerc_gripper_t *playerc_gripper_create(playerc_client_t *client, int index);
01742
01744 void playerc_gripper_destroy(playerc_gripper_t *device);
01745
01747 int playerc_gripper_subscribe(playerc_gripper_t *device, int access);
01748
01750 int playerc_gripper_unsubscribe(playerc_gripper_t *device);
01751
01753 int playerc_gripper_open_cmd(playerc_gripper_t *device);
01754
01756 int playerc_gripper_close_cmd(playerc_gripper_t *device);
01757
01759 int playerc_gripper_stop_cmd(playerc_gripper_t *device);
01760
01762 int playerc_gripper_store_cmd(playerc_gripper_t *device);
01763
01765 int playerc_gripper_retrieve_cmd(playerc_gripper_t *device);
01766
01769 void playerc_gripper_printout(playerc_gripper_t *device, const char* prefix);
01770
01775 int playerc_gripper_get_geom(playerc_gripper_t *device);
01776
01778
01779
01780
01794 typedef struct
01795 {
01797 playerc_device_t info;
01799 player_health_cpu_t cpu_usage;
01801 player_health_memory_t mem;
01803 player_health_memory_t swap;
01804 } playerc_health_t;
01805
01806
01808 playerc_health_t *playerc_health_create(playerc_client_t *client, int index);
01809
01811 void playerc_health_destroy(playerc_health_t *device);
01812
01814 int playerc_health_subscribe(playerc_health_t *device, int access);
01815
01817 int playerc_health_unsubscribe(playerc_health_t *device);
01818
01819
01821
01822
01823
01824
01835 typedef struct
01836 {
01838 playerc_device_t info;
01839
01840
01841 player_ir_data_t data;
01842
01843
01844 player_ir_pose_t poses;
01845
01846 } playerc_ir_t;
01847
01848
01850 playerc_ir_t *playerc_ir_create(playerc_client_t *client, int index);
01851
01853 void playerc_ir_destroy(playerc_ir_t *device);
01854
01856 int playerc_ir_subscribe(playerc_ir_t *device, int access);
01857
01859 int playerc_ir_unsubscribe(playerc_ir_t *device);
01860
01867 int playerc_ir_get_geom(playerc_ir_t *device);
01868
01869
01871
01872
01873
01874
01875
01889 typedef struct
01890 {
01892 playerc_device_t info;
01893
01897 double pose[3];
01898 double size[2];
01899
01901 double robot_pose[3];
01902
01904 int intensity_on;
01905
01907 int scan_count;
01908
01910 double scan_start;
01911
01913 double scan_res;
01914
01916 double range_res;
01917
01919 double max_range;
01920
01922 double scanning_frequency;
01923
01925 double *ranges;
01926
01928 double (*scan)[2];
01929
01931 player_point_2d_t *point;
01932
01936 int *intensity;
01937
01939 int scan_id;
01940
01942 int laser_id;
01943
01947 double min_right;
01948
01952 double min_left;
01953 } playerc_laser_t;
01954
01955
01957 playerc_laser_t *playerc_laser_create(playerc_client_t *client, int index);
01958
01960 void playerc_laser_destroy(playerc_laser_t *device);
01961
01963 int playerc_laser_subscribe(playerc_laser_t *device, int access);
01964
01966 int playerc_laser_unsubscribe(playerc_laser_t *device);
01967
01990 int playerc_laser_set_config(playerc_laser_t *device,
01991 double min_angle, double max_angle,
01992 double resolution,
01993 double range_res,
01994 unsigned char intensity,
01995 double scanning_frequency);
01996
02019 int playerc_laser_get_config(playerc_laser_t *device,
02020 double *min_angle,
02021 double *max_angle,
02022 double *resolution,
02023 double *range_res,
02024 unsigned char *intensity,
02025 double *scanning_frequency);
02026
02033 int playerc_laser_get_geom(playerc_laser_t *device);
02034
02039 int playerc_laser_get_id (playerc_laser_t *device);
02040
02043 void playerc_laser_printout( playerc_laser_t * device,
02044 const char* prefix );
02045
02047
02048
02049
02061 typedef struct
02062 {
02064 playerc_device_t info;
02065
02066 player_limb_data_t data;
02067 player_limb_geom_req_t geom;
02068 } playerc_limb_t;
02069
02071 playerc_limb_t *playerc_limb_create(playerc_client_t *client, int index);
02072
02074 void playerc_limb_destroy(playerc_limb_t *device);
02075
02077 int playerc_limb_subscribe(playerc_limb_t *device, int access);
02078
02080 int playerc_limb_unsubscribe(playerc_limb_t *device);
02081
02084 int playerc_limb_get_geom(playerc_limb_t *device);
02085
02087 int playerc_limb_home_cmd(playerc_limb_t *device);
02088
02090 int playerc_limb_stop_cmd(playerc_limb_t *device);
02091
02093 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);
02094
02097 int playerc_limb_setposition_cmd(playerc_limb_t *device, float pX, float pY, float pZ);
02098
02101 int playerc_limb_vecmove_cmd(playerc_limb_t *device, float x, float y, float z, float length);
02102
02106 int playerc_limb_power(playerc_limb_t *device, uint32_t enable);
02107
02109 int playerc_limb_brakes(playerc_limb_t *device, uint32_t enable);
02110
02112 int playerc_limb_speed_config(playerc_limb_t *device, float speed);
02113
02115
02116
02117
02118
02135 typedef struct playerc_localize_particle
02136 {
02137 double pose[3];
02138 double weight;
02139 } playerc_localize_particle_t;
02140
02141
02143 typedef struct
02144 {
02146 playerc_device_t info;
02147
02149 int map_size_x, map_size_y;
02150
02152 double map_scale;
02153
02155 int map_tile_x, map_tile_y;
02156
02158 int8_t *map_cells;
02159
02161 int pending_count;
02162
02164 double pending_time;
02165
02167 int hypoth_count;
02168 player_localize_hypoth_t *hypoths;
02169
02170 double mean[3];
02171 double variance;
02172 int num_particles;
02173 playerc_localize_particle_t *particles;
02174
02175 } playerc_localize_t;
02176
02177
02179 playerc_localize_t *playerc_localize_create(playerc_client_t *client, int index);
02180
02182 void playerc_localize_destroy(playerc_localize_t *device);
02183
02185 int playerc_localize_subscribe(playerc_localize_t *device, int access);
02186
02188 int playerc_localize_unsubscribe(playerc_localize_t *device);
02189
02191 int playerc_localize_set_pose(playerc_localize_t *device, double pose[3], double cov[3]);
02192
02195 int playerc_localize_get_particles(playerc_localize_t *device);
02196
02198
02199
02200
02201
02211 typedef struct
02212 {
02214 playerc_device_t info;
02215
02218 int type;
02219
02222 int state;
02223 } playerc_log_t;
02224
02225
02227 playerc_log_t *playerc_log_create(playerc_client_t *client, int index);
02228
02230 void playerc_log_destroy(playerc_log_t *device);
02231
02233 int playerc_log_subscribe(playerc_log_t *device, int access);
02234
02236 int playerc_log_unsubscribe(playerc_log_t *device);
02237
02239 int playerc_log_set_write_state(playerc_log_t* device, int state);
02240
02242 int playerc_log_set_read_state(playerc_log_t* device, int state);
02243
02245 int playerc_log_set_read_rewind(playerc_log_t* device);
02246
02252 int playerc_log_get_state(playerc_log_t* device);
02253
02255 int playerc_log_set_filename(playerc_log_t* device, const char* fname);
02256
02257
02261
02271 typedef struct
02272 {
02274 playerc_device_t info;
02275
02277 double resolution;
02278
02280 int width, height;
02281
02283 double origin[2];
02284
02286 char* cells;
02287
02290 double vminx, vminy, vmaxx, vmaxy;
02291 int num_segments;
02292 player_segment_t* segments;
02293 } playerc_map_t;
02294
02297 #define PLAYERC_MAP_INDEX(dev, i, j) ((dev->width) * (j) + (i))
02298
02300 playerc_map_t *playerc_map_create(playerc_client_t *client, int index);
02301
02303 void playerc_map_destroy(playerc_map_t *device);
02304
02306 int playerc_map_subscribe(playerc_map_t *device, int access);
02307
02309 int playerc_map_unsubscribe(playerc_map_t *device);
02310
02312 int playerc_map_get_map(playerc_map_t* device);
02313
02315 int playerc_map_get_vector(playerc_map_t* device);
02316
02318
02319
02328 typedef struct
02329 {
02331 playerc_device_t info;
02333 uint32_t srid;
02335 player_extent2d_t extent;
02337 uint32_t layers_count;
02339 player_vectormap_layer_data_t** layers_data;
02341 player_vectormap_layer_info_t** layers_info;
02343 GEOSGeom geom;
02344
02345 } playerc_vectormap_t;
02346
02348 playerc_vectormap_t *playerc_vectormap_create(playerc_client_t *client, int index);
02349
02351 void playerc_vectormap_destroy(playerc_vectormap_t *device);
02352
02354 int playerc_vectormap_subscribe(playerc_vectormap_t *device, int access);
02355
02357 int playerc_vectormap_unsubscribe(playerc_vectormap_t *device);
02358
02360 int playerc_vectormap_get_map_info(playerc_vectormap_t* device);
02361
02363 int playerc_vectormap_get_layer_data(playerc_vectormap_t *device, unsigned layer_index);
02364
02366 int playerc_vectormap_write_layer(playerc_vectormap_t *device, const player_vectormap_layer_data_t * data);
02367
02369 void playerc_vectormap_cleanup(playerc_vectormap_t *device);
02370
02373 GEOSGeom playerc_vectormap_get_feature_data(playerc_vectormap_t *device, unsigned layer_index, unsigned feature_index);
02374
02377
02388 typedef struct
02389 {
02391 playerc_device_t info;
02392
02394 int data_count;
02395
02397 uint8_t *data;
02398 } playerc_opaque_t;
02399
02401 playerc_opaque_t *playerc_opaque_create(playerc_client_t *client, int index);
02402
02404 void playerc_opaque_destroy(playerc_opaque_t *device);
02405
02407 int playerc_opaque_subscribe(playerc_opaque_t *device, int access);
02408
02410 int playerc_opaque_unsubscribe(playerc_opaque_t *device);
02411
02413 int playerc_opaque_cmd(playerc_opaque_t *device, player_opaque_data_t *data);
02414
02421 int playerc_opaque_req(playerc_opaque_t *device, player_opaque_data_t *request, player_opaque_data_t **reply);
02422
02424
02425
02426
02427
02437 typedef struct
02438 {
02440 playerc_device_t info;
02441
02443 int path_valid;
02444
02446 int path_done;
02447
02449 double px, py, pa;
02450
02452 double gx, gy, ga;
02453
02455 double wx, wy, wa;
02456
02460 int curr_waypoint;
02461
02463 int waypoint_count;
02464
02467 double (*waypoints)[3];
02468
02469 } playerc_planner_t;
02470
02472 playerc_planner_t *playerc_planner_create(playerc_client_t *client, int index);
02473
02475 void playerc_planner_destroy(playerc_planner_t *device);
02476
02478 int playerc_planner_subscribe(playerc_planner_t *device, int access);
02479
02481 int playerc_planner_unsubscribe(playerc_planner_t *device);
02482
02484 int playerc_planner_set_cmd_pose(playerc_planner_t *device,
02485 double gx, double gy, double ga);
02486
02493 int playerc_planner_get_waypoints(playerc_planner_t *device);
02494
02500 int playerc_planner_enable(playerc_planner_t *device, int state);
02501
02503
02504
02505
02516 typedef struct
02517 {
02519 playerc_device_t info;
02520
02524 double pose[3];
02525 double size[2];
02526
02528 double pos;
02529
02531 double vel;
02532
02534 int stall;
02535
02547 int status;
02548
02549 } playerc_position1d_t;
02550
02552 playerc_position1d_t *playerc_position1d_create(playerc_client_t *client,
02553 int index);
02554
02556 void playerc_position1d_destroy(playerc_position1d_t *device);
02557
02559 int playerc_position1d_subscribe(playerc_position1d_t *device, int access);
02560
02562 int playerc_position1d_unsubscribe(playerc_position1d_t *device);
02563
02565 int playerc_position1d_enable(playerc_position1d_t *device, int enable);
02566
02569 int playerc_position1d_get_geom(playerc_position1d_t *device);
02570
02572 int playerc_position1d_set_cmd_vel(playerc_position1d_t *device,
02573 double vel, int state);
02574
02578 int playerc_position1d_set_cmd_pos(playerc_position1d_t *device,
02579 double pos, int state);
02580
02585 int playerc_position1d_set_cmd_pos_with_vel(playerc_position1d_t *device,
02586 double pos, double vel, int state);
02587
02589 int playerc_position1d_set_odom(playerc_position1d_t *device,
02590 double odom);
02591
02593
02594
02595
02596
02610 typedef struct
02611 {
02613 playerc_device_t info;
02614
02618 double pose[3];
02619 double size[2];
02620
02622 double px, py, pa;
02623
02625 double vx, vy, va;
02626
02628 int stall;
02629
02630 } playerc_position2d_t;
02631
02633 playerc_position2d_t *playerc_position2d_create(playerc_client_t *client,
02634 int index);
02635
02637 void playerc_position2d_destroy(playerc_position2d_t *device);
02638
02640 int playerc_position2d_subscribe(playerc_position2d_t *device, int access);
02641
02643 int playerc_position2d_unsubscribe(playerc_position2d_t *device);
02644
02646 int playerc_position2d_enable(playerc_position2d_t *device, int enable);
02647
02650 int playerc_position2d_get_geom(playerc_position2d_t *device);
02651
02656 int playerc_position2d_set_cmd_vel(playerc_position2d_t *device,
02657 double vx, double vy, double va, int state);
02658
02660 int playerc_position2d_set_cmd_pose_with_vel(playerc_position2d_t *device,
02661 player_pose2d_t pos,
02662 player_pose2d_t vel,
02663 int state);
02664
02667 int playerc_position2d_set_cmd_pose(playerc_position2d_t *device,
02668 double gx, double gy, double ga, int state);
02669
02671 int playerc_position2d_set_cmd_car(playerc_position2d_t *device,
02672 double vx, double a);
02673
02675 int playerc_position2d_set_odom(playerc_position2d_t *device,
02676 double ox, double oy, double oa);
02677
02679
02680
02681
02696 typedef struct
02697 {
02699 playerc_device_t info;
02700
02704 double pose[3];
02705 double size[2];
02706
02708 double pos_x, pos_y, pos_z;
02709
02711 double pos_roll, pos_pitch, pos_yaw;
02712
02714 double vel_x, vel_y, vel_z;
02715
02717 double vel_roll, vel_pitch, vel_yaw;
02718
02720 int stall;
02721
02722 } playerc_position3d_t;
02723
02724
02726 playerc_position3d_t *playerc_position3d_create(playerc_client_t *client,
02727 int index);
02728
02730 void playerc_position3d_destroy(playerc_position3d_t *device);
02731
02733 int playerc_position3d_subscribe(playerc_position3d_t *device, int access);
02734
02736 int playerc_position3d_unsubscribe(playerc_position3d_t *device);
02737
02739 int playerc_position3d_enable(playerc_position3d_t *device, int enable);
02740
02743 int playerc_position3d_get_geom(playerc_position3d_t *device);
02744
02749 int playerc_position3d_set_velocity(playerc_position3d_t *device,
02750 double vx, double vy, double vz,
02751 double vr, double vp, double vt,
02752 int state);
02753
02755 int playerc_position3d_set_speed(playerc_position3d_t *device,
02756 double vx, double vy, double vz, int state);
02757
02760 int playerc_position3d_set_pose(playerc_position3d_t *device,
02761 double gx, double gy, double gz,
02762 double gr, double gp, double gt);
02763
02764
02766 int playerc_position3d_set_pose_with_vel(playerc_position3d_t *device,
02767 player_pose3d_t pos,
02768 player_pose3d_t vel);
02769
02771 int playerc_position3d_set_cmd_pose(playerc_position3d_t *device,
02772 double gx, double gy, double gz);
02773
02775 int playerc_position3d_set_vel_mode(playerc_position3d_t *device, int mode);
02776
02778 int playerc_position3d_set_odom(playerc_position3d_t *device,
02779 double ox, double oy, double oz,
02780 double oroll, double opitch, double oyaw);
02781
02783 int playerc_position3d_reset_odom(playerc_position3d_t *device);
02784
02786
02787
02788
02789
02800 typedef struct
02801 {
02803 playerc_device_t info;
02804
02807 int valid;
02808
02810 double charge;
02811
02813 double percent;
02814
02816 double joules;
02817
02820 double watts;
02821
02823 int charging;
02824
02825 } playerc_power_t;
02826
02827
02829 playerc_power_t *playerc_power_create(playerc_client_t *client, int index);
02830
02832 void playerc_power_destroy(playerc_power_t *device);
02833
02835 int playerc_power_subscribe(playerc_power_t *device, int access);
02836
02838 int playerc_power_unsubscribe(playerc_power_t *device);
02839
02840
02842
02843
02844
02845
02846
02857 typedef struct
02858 {
02860 playerc_device_t info;
02861
02865 double pan, tilt;
02866
02868 double zoom;
02869
02871 int status;
02872 } playerc_ptz_t;
02873
02874
02876 playerc_ptz_t *playerc_ptz_create(playerc_client_t *client, int index);
02877
02879 void playerc_ptz_destroy(playerc_ptz_t *device);
02880
02882 int playerc_ptz_subscribe(playerc_ptz_t *device, int access);
02883
02885 int playerc_ptz_unsubscribe(playerc_ptz_t *device);
02886
02895 int playerc_ptz_set(playerc_ptz_t *device, double pan, double tilt, double zoom);
02896
02902 int playerc_ptz_query_status(playerc_ptz_t *device);
02903
02914 int playerc_ptz_set_ws(playerc_ptz_t *device, double pan, double tilt, double zoom,
02915 double panspeed, double tiltspeed);
02916
02924 int playerc_ptz_set_control_mode(playerc_ptz_t *device, int mode);
02925
02927
02928
02929
02939 typedef struct
02940 {
02942 playerc_device_t info;
02943
02945 uint32_t sensor_count;
02946
02948 double min_angle;
02950 double max_angle;
02952 double resolution;
02954 double max_range;
02956 double range_res;
02958 double frequency;
02959
02963 player_pose3d_t device_pose;
02964 player_bbox3d_t device_size;
02968 player_pose3d_t *sensor_poses;
02969 player_bbox3d_t *sensor_sizes;
02970
02972 uint32_t ranges_count;
02974 double *ranges;
02975
02977 uint32_t intensities_count;
02981 double *intensities;
02982
02983 } playerc_ranger_t;
02984
02986 playerc_ranger_t *playerc_ranger_create(playerc_client_t *client, int index);
02987
02989 void playerc_ranger_destroy(playerc_ranger_t *device);
02990
02992 int playerc_ranger_subscribe(playerc_ranger_t *device, int access);
02993
02995 int playerc_ranger_unsubscribe(playerc_ranger_t *device);
02996
03001 int playerc_ranger_get_geom(playerc_ranger_t *device);
03002
03006 int playerc_ranger_power_config(playerc_ranger_t *device, uint8_t value);
03007
03011 int playerc_ranger_intns_config(playerc_ranger_t *device, uint8_t value);
03012
03021 int playerc_ranger_set_config(playerc_ranger_t *device, double min_angle,
03022 double max_angle, double resolution,
03023 double max_range, double range_res,
03024 double frequency);
03025
03034 int playerc_ranger_get_config(playerc_ranger_t *device, double *min_angle,
03035 double *max_angle, double *resolution,
03036 double *max_range, double *range_res,
03037 double *frequency);
03038
03040
03041
03042
03053 typedef struct
03054 {
03056 playerc_device_t info;
03057
03059 int pose_count;
03060
03063 player_pose3d_t *poses;
03064
03066 int scan_count;
03067
03069 double *scan;
03070
03071 } playerc_sonar_t;
03072
03073
03075 playerc_sonar_t *playerc_sonar_create(playerc_client_t *client, int index);
03076
03078 void playerc_sonar_destroy(playerc_sonar_t *device);
03079
03081 int playerc_sonar_subscribe(playerc_sonar_t *device, int access);
03082
03084 int playerc_sonar_unsubscribe(playerc_sonar_t *device);
03085
03091 int playerc_sonar_get_geom(playerc_sonar_t *device);
03092
03094
03095
03096
03108 typedef struct
03109 {
03111 uint8_t mac[32];
03112
03114 uint8_t ip[32];
03115
03117 uint8_t essid[32];
03118
03120 int mode;
03121
03123 int encrypt;
03124
03126 double freq;
03127
03129 int qual, level, noise;
03130
03131 } playerc_wifi_link_t;
03132
03133
03135 typedef struct
03136 {
03138 playerc_device_t info;
03139
03141 playerc_wifi_link_t *links;
03142 int link_count;
03143 char ip[32];
03144 } playerc_wifi_t;
03145
03146
03148 playerc_wifi_t *playerc_wifi_create(playerc_client_t *client, int index);
03149
03151 void playerc_wifi_destroy(playerc_wifi_t *device);
03152
03154 int playerc_wifi_subscribe(playerc_wifi_t *device, int access);
03155
03157 int playerc_wifi_unsubscribe(playerc_wifi_t *device);
03158
03160 playerc_wifi_link_t *playerc_wifi_get_link(playerc_wifi_t *device, int link);
03161
03162
03164
03165
03166
03178 typedef struct
03179 {
03181 playerc_device_t info;
03182
03183 } playerc_simulation_t;
03184
03185
03187 playerc_simulation_t *playerc_simulation_create(playerc_client_t *client, int index);
03188
03190 void playerc_simulation_destroy(playerc_simulation_t *device);
03191
03193 int playerc_simulation_subscribe(playerc_simulation_t *device, int access);
03194
03196 int playerc_simulation_unsubscribe(playerc_simulation_t *device);
03197
03199 int playerc_simulation_set_pose2d(playerc_simulation_t *device, char* name,
03200 double gx, double gy, double ga);
03201
03203 int playerc_simulation_get_pose2d(playerc_simulation_t *device, char* identifier,
03204 double *x, double *y, double *a);
03205
03207 int playerc_simulation_set_pose3d(playerc_simulation_t *device, char* name,
03208 double gx, double gy, double gz,
03209 double groll, double gpitch, double gyaw);
03210
03212 int playerc_simulation_get_pose3d(playerc_simulation_t *device, char* identifier,
03213 double *x, double *y, double *z,
03214 double *roll, double *pitch, double *yaw, double *time);
03215
03217 int playerc_simulation_set_property(playerc_simulation_t *device,
03218 char* name,
03219 char* property,
03220 void* value,
03221 size_t value_len);
03222
03224 int playerc_simulation_get_property(playerc_simulation_t *device,
03225 char* name,
03226 char* property,
03227 void* value,
03228 size_t value_len);
03230
03231
03232
03233
03243 typedef struct
03244 {
03246 playerc_device_t info;
03247 } playerc_speech_t;
03248
03249
03251 playerc_speech_t *playerc_speech_create(playerc_client_t *client, int index);
03252
03254 void playerc_speech_destroy(playerc_speech_t *device);
03255
03257 int playerc_speech_subscribe(playerc_speech_t *device, int access);
03258
03260 int playerc_speech_unsubscribe(playerc_speech_t *device);
03261
03263 int playerc_speech_say (playerc_speech_t *device, char *);
03264
03265
03267
03268
03269
03279 typedef struct
03280 {
03282 playerc_device_t info;
03283
03284 char *rawText;
03285
03286
03287 char **words;
03288 int wordCount;
03289 } playerc_speechrecognition_t;
03290
03291
03293 playerc_speechrecognition_t *playerc_speechrecognition_create(playerc_client_t *client, int index);
03294
03296 void playerc_speechrecognition_destroy(playerc_speechrecognition_t *device);
03297
03299 int playerc_speechrecognition_subscribe(playerc_speechrecognition_t *device, int access);
03300
03302 int playerc_speechrecognition_unsubscribe(playerc_speechrecognition_t *device);
03303
03305
03306
03307
03317 typedef struct
03318 {
03320 uint32_t type;
03322 uint32_t guid_count;
03324 uint8_t *guid;
03325 } playerc_rfidtag_t;
03326
03328 typedef struct
03329 {
03331 playerc_device_t info;
03332
03334 uint16_t tags_count;
03335
03337 playerc_rfidtag_t *tags;
03338 } playerc_rfid_t;
03339
03340
03342 playerc_rfid_t *playerc_rfid_create(playerc_client_t *client, int index);
03343
03345 void playerc_rfid_destroy(playerc_rfid_t *device);
03346
03348 int playerc_rfid_subscribe(playerc_rfid_t *device, int access);
03349
03351 int playerc_rfid_unsubscribe(playerc_rfid_t *device);
03352
03354
03355
03356
03366 typedef player_pointcloud3d_element_t playerc_pointcloud3d_element_t;
03367
03369 typedef struct
03370 {
03372 playerc_device_t info;
03373
03375 uint16_t points_count;
03376
03378 playerc_pointcloud3d_element_t *points;
03379 } playerc_pointcloud3d_t;
03380
03381
03383 playerc_pointcloud3d_t *playerc_pointcloud3d_create (playerc_client_t *client, int index);
03384
03386 void playerc_pointcloud3d_destroy (playerc_pointcloud3d_t *device);
03387
03389 int playerc_pointcloud3d_subscribe (playerc_pointcloud3d_t *device, int access);
03390
03392 int playerc_pointcloud3d_unsubscribe (playerc_pointcloud3d_t *device);
03393
03395
03396
03397
03407 typedef struct
03408 {
03410 playerc_device_t info;
03411
03413 player_pose3d_t pose;
03414
03416 player_imu_data_calib_t calib_data;
03417
03419 float q0, q1, q2, q3;
03420 } playerc_imu_t;
03421
03423 playerc_imu_t *playerc_imu_create (playerc_client_t *client, int index);
03424
03426 void playerc_imu_destroy (playerc_imu_t *device);
03427
03429 int playerc_imu_subscribe (playerc_imu_t *device, int access);
03430
03432 int playerc_imu_unsubscribe (playerc_imu_t *device);
03433
03435 int playerc_imu_datatype (playerc_imu_t *device, int value);
03436
03438 int playerc_imu_reset_orientation (playerc_imu_t *device, int value);
03439
03441
03442
03443
03456 typedef struct
03457 {
03459 playerc_device_t info;
03460
03462 uint32_t node_type;
03464 uint32_t node_id;
03466 uint32_t node_parent_id;
03468 player_wsn_node_data_t data_packet;
03469 } playerc_wsn_t;
03470
03471
03473 playerc_wsn_t *playerc_wsn_create(playerc_client_t *client, int index);
03474
03476 void playerc_wsn_destroy(playerc_wsn_t *device);
03477
03479 int playerc_wsn_subscribe(playerc_wsn_t *device, int access);
03480
03482 int playerc_wsn_unsubscribe(playerc_wsn_t *device);
03483
03485 int playerc_wsn_set_devstate(playerc_wsn_t *device, int node_id,
03486 int group_id, int devnr, int state);
03487
03489 int playerc_wsn_power(playerc_wsn_t *device, int node_id, int group_id,
03490 int value);
03491
03493 int playerc_wsn_datatype(playerc_wsn_t *device, int value);
03494
03496 int playerc_wsn_datafreq(playerc_wsn_t *device, int node_id, int group_id,
03497 double frequency);
03498
03500
03501
03502 #ifdef __cplusplus
03503 }
03504 #endif
03505
03506 #endif