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
00047 #ifndef PLAYERC_H
00048 #define PLAYERC_H
00049
00050 #include <stdio.h>
00051 #include <sys/types.h>
00052 #include <netinet/in.h>
00053
00054
00055 #include <libplayercore/player.h>
00056 #include <libplayercore/playercommon.h>
00057 #include <libplayercore/error.h>
00058 #include <libplayerxdr/playerxdr.h>
00059
00060 #ifndef MIN
00061 #define MIN(a,b) ((a < b) ? a : b)
00062 #endif
00063 #ifndef MAX
00064 #define MAX(a,b) ((a > b) ? a : b)
00065 #endif
00066
00067 #ifdef __cplusplus
00068 extern "C" {
00069 #endif
00070
00071
00072
00073
00074
00075
00077 #define PLAYERC_OPEN_MODE PLAYER_OPEN_MODE
00078 #define PLAYERC_CLOSE_MODE PLAYER_CLOSE_MODE
00079 #define PLAYERC_ERROR_MODE PLAYER_ERROR_MODE
00080
00081
00083 #define PLAYERC_DATAMODE_PUSH PLAYER_DATAMODE_PUSH
00084 #define PLAYERC_DATAMODE_PULL PLAYER_DATAMODE_PULL
00085
00087 #define PLAYERC_TRANSPORT_TCP 1
00088 #define PLAYERC_TRANSPORT_UDP 2
00089
00090
00091
00092
00093
00094 #define PLAYERC_MAX_DEVICES PLAYER_MAX_DEVICES
00095 #define PLAYERC_LASER_MAX_SAMPLES PLAYER_LASER_MAX_SAMPLES
00096 #define PLAYERC_FIDUCIAL_MAX_SAMPLES PLAYER_FIDUCIAL_MAX_SAMPLES
00097 #define PLAYERC_SONAR_MAX_SAMPLES PLAYER_SONAR_MAX_SAMPLES
00098 #define PLAYERC_BUMPER_MAX_SAMPLES PLAYER_BUMPER_MAX_SAMPLES
00099 #define PLAYERC_IR_MAX_SAMPLES PLAYER_IR_MAX_SAMPLES
00100 #define PLAYERC_BLOBFINDER_MAX_BLOBS PLAYER_BLOBFINDER_MAX_BLOBS
00101 #define PLAYERC_WIFI_MAX_LINKS PLAYER_WIFI_MAX_LINKS
00102 #define PLAYERC_RFID_MAX_TAGS PLAYER_RFID_MAX_TAGS
00103 #define PLAYERC_RFID_MAX_GUID PLAYER_RFID_MAX_GUID
00104
00318
00324
00325
00330 const char *playerc_error_str(void);
00331
00333 const char *playerc_lookup_name(int code);
00334
00336 int playerc_lookup_code(const char *name);
00337
00339
00340
00341
00342
00343 struct _playerc_client_t;
00344 struct _playerc_device_t;
00345
00346
00347
00348
00349 struct pollfd;
00350
00351
00352
00363
00364 typedef struct
00365 {
00366 player_msghdr_t header;
00367 void *data;
00368 } playerc_client_item_t;
00369
00370
00371
00372 typedef struct
00373 {
00374
00375 int client_count;
00376 struct _playerc_client_t *client[128];
00377
00378
00379 struct pollfd* pollfd;
00380
00381
00382 double time;
00383
00384 } playerc_mclient_t;
00385
00386
00387 playerc_mclient_t *playerc_mclient_create(void);
00388
00389
00390 void playerc_mclient_destroy(playerc_mclient_t *mclient);
00391
00392
00393 int playerc_mclient_addclient(playerc_mclient_t *mclient, struct _playerc_client_t *client);
00394
00395
00396
00397 int playerc_mclient_peek(playerc_mclient_t *mclient, int timeout);
00398
00399
00400
00401 int playerc_mclient_read(playerc_mclient_t *mclient, int timeout);
00402
00404
00405
00406
00407
00420 typedef void (*playerc_putmsg_fn_t) (void *device, char *header, char *data);
00421
00423 typedef void (*playerc_callback_fn_t) (void *data);
00424
00425
00429 typedef struct
00430 {
00432 player_devaddr_t addr;
00433
00435 char drivername[PLAYER_MAX_DRIVER_STRING_LEN];
00436
00437 } playerc_device_info_t;
00438
00439
00441 typedef struct _playerc_client_t
00442 {
00445 void *id;
00446
00448 char *host;
00449 int port;
00450 int transport;
00451 struct sockaddr_in server;
00452
00456 int retry_limit;
00457
00460 double retry_time;
00461
00463 int sock;
00464
00466 uint8_t mode;
00467
00470 playerc_device_info_t devinfos[PLAYERC_MAX_DEVICES];
00471 int devinfo_count;
00472
00474 struct _playerc_device_t *device[32];
00475 int device_count;
00476
00478 playerc_client_item_t qitems[512];
00479 int qfirst, qlen, qsize;
00480
00482 char *data;
00483 char *write_xdrdata;
00484 char *read_xdrdata;
00485 size_t read_xdrdata_len;
00486
00487
00489 double datatime;
00491 double lasttime;
00492
00493 double request_timeout;
00494
00495 } playerc_client_t;
00496
00497
00513 playerc_client_t *playerc_client_create(playerc_mclient_t *mclient,
00514 const char *host, int port);
00515
00521 void playerc_client_destroy(playerc_client_t *client);
00522
00527 void playerc_client_set_transport(playerc_client_t* client,
00528 unsigned int transport);
00529
00538 int playerc_client_connect(playerc_client_t *client);
00539
00548 int playerc_client_disconnect(playerc_client_t *client);
00549
00564 int playerc_client_datamode(playerc_client_t *client, uint8_t mode);
00565
00577 int playerc_client_requestdata(playerc_client_t* client);
00578
00601 int playerc_client_set_replace_rule(playerc_client_t *client, int interf, int index, int type, int subtype, int replace);
00602
00603
00606 int playerc_client_adddevice(playerc_client_t *client, struct _playerc_device_t *device);
00607
00608
00611 int playerc_client_deldevice(playerc_client_t *client, struct _playerc_device_t *device);
00612
00615 int playerc_client_addcallback(playerc_client_t *client, struct _playerc_device_t *device,
00616 playerc_callback_fn_t callback, void *data);
00617
00620 int playerc_client_delcallback(playerc_client_t *client, struct _playerc_device_t *device,
00621 playerc_callback_fn_t callback, void *data);
00622
00634 int playerc_client_get_devlist(playerc_client_t *client);
00635
00638 int playerc_client_subscribe(playerc_client_t *client, int code, int index,
00639 int access, char *drivername, size_t len);
00640
00643 int playerc_client_unsubscribe(playerc_client_t *client, int code, int index);
00644
00650 int playerc_client_request(playerc_client_t *client,
00651 struct _playerc_device_t *device, uint8_t reqtype,
00652 void *req_data, void *rep_data, int rep_len);
00653
00664
00665
00666
00677 int playerc_client_peek(playerc_client_t *client, int timeout);
00678
00690 void *playerc_client_read(playerc_client_t *client);
00691
00692
00699 void playerc_client_set_request_timeout(playerc_client_t* client, uint seconds);
00700
00707 void playerc_client_set_retry_limit(playerc_client_t* client, int limit);
00708
00714 void playerc_client_set_retry_time(playerc_client_t* client, double time);
00715
00718 int playerc_client_write(playerc_client_t *client,
00719 struct _playerc_device_t *device,
00720 uint8_t subtype,
00721 void *cmd, double* timestamp);
00722
00723
00725
00726
00727
00728
00741 typedef struct _playerc_device_t
00742 {
00746 void *id;
00747
00749 playerc_client_t *client;
00750
00752 player_devaddr_t addr;
00753
00755 char drivername[PLAYER_MAX_DRIVER_STRING_LEN];
00756
00759 int subscribed;
00760
00762 double datatime;
00763
00765 double lasttime;
00766
00770 int fresh;
00774 int freshgeom;
00778 int freshconfig;
00779
00781 playerc_putmsg_fn_t putmsg;
00782
00784 void *user_data;
00785
00787 int callback_count;
00788 playerc_callback_fn_t callback[4];
00789 void *callback_data[4];
00790
00791 } playerc_device_t;
00792
00793
00795 void playerc_device_init(playerc_device_t *device, playerc_client_t *client,
00796 int code, int index, playerc_putmsg_fn_t putmsg);
00797
00799 void playerc_device_term(playerc_device_t *device);
00800
00802 int playerc_device_subscribe(playerc_device_t *device, int access);
00803
00805 int playerc_device_unsubscribe(playerc_device_t *device);
00806
00808
00809
00810
00811
00816
00817
00818
00828 typedef struct
00829 {
00831 playerc_device_t info;
00832
00834 uint8_t voltages_count;
00835
00837 float voltages[PLAYER_AIO_MAX_INPUTS];
00838
00839 } playerc_aio_t;
00840
00841
00843 playerc_aio_t *playerc_aio_create(playerc_client_t *client, int index);
00844
00846 void playerc_aio_destroy(playerc_aio_t *device);
00847
00849 int playerc_aio_subscribe(playerc_aio_t *device, int access);
00850
00852 int playerc_aio_unsubscribe(playerc_aio_t *device);
00853
00855 int playerc_aio_set_output(playerc_aio_t *device, uint8_t id, float volt);
00856
00858
00859
00860
00861
00873 typedef struct
00874 {
00876 playerc_device_t info;
00877
00879 uint32_t actuators_count;
00881 player_actarray_actuator_t actuators_data[PLAYER_ACTARRAY_NUM_ACTUATORS];
00882 player_actarray_actuatorgeom_t actuators_geom[PLAYER_ACTARRAY_NUM_ACTUATORS];
00883 } playerc_actarray_t;
00884
00886 playerc_actarray_t *playerc_actarray_create(playerc_client_t *client, int index);
00887
00889 void playerc_actarray_destroy(playerc_actarray_t *device);
00890
00892 int playerc_actarray_subscribe(playerc_actarray_t *device, int access);
00893
00895 int playerc_actarray_unsubscribe(playerc_actarray_t *device);
00896
00899 int playerc_actarray_get_geom(playerc_actarray_t *device);
00900
00902 int playerc_actarray_position_cmd(playerc_actarray_t *device, int joint, float position);
00903
00905 int playerc_actarray_speed_cmd(playerc_actarray_t *device, int joint, float speed);
00906
00908 int playerc_actarray_home_cmd(playerc_actarray_t *device, int joint);
00909
00913 int playerc_actarray_power(playerc_actarray_t *device, uint8_t enable);
00914
00916 int playerc_actarray_brakes(playerc_actarray_t *device, uint8_t enable);
00917
00919 int playerc_actarray_speed_config(playerc_actarray_t *device, int joint, float speed);
00920
00922
00923
00924
00925
00936 typedef player_blobfinder_blob_t playerc_blobfinder_blob_t;
00937
00939 typedef struct
00940 {
00942 playerc_device_t info;
00943
00945 unsigned int width, height;
00946
00948 unsigned int blobs_count;
00949 playerc_blobfinder_blob_t blobs[PLAYER_BLOBFINDER_MAX_BLOBS];
00950
00951 } playerc_blobfinder_t;
00952
00953
00955 playerc_blobfinder_t *playerc_blobfinder_create(playerc_client_t *client, int index);
00956
00958 void playerc_blobfinder_destroy(playerc_blobfinder_t *device);
00959
00961 int playerc_blobfinder_subscribe(playerc_blobfinder_t *device, int access);
00962
00964 int playerc_blobfinder_unsubscribe(playerc_blobfinder_t *device);
00965
00966
00968
00969
00970
00971
00982 typedef struct
00983 {
00985 playerc_device_t info;
00986
00988 int pose_count;
00989
00993 player_bumper_define_t poses[PLAYERC_BUMPER_MAX_SAMPLES];
00994
00996 int bumper_count;
00997
00999 uint8_t bumpers[PLAYERC_BUMPER_MAX_SAMPLES];
01000
01001 } playerc_bumper_t;
01002
01003
01005 playerc_bumper_t *playerc_bumper_create(playerc_client_t *client, int index);
01006
01008 void playerc_bumper_destroy(playerc_bumper_t *device);
01009
01011 int playerc_bumper_subscribe(playerc_bumper_t *device, int access);
01012
01014 int playerc_bumper_unsubscribe(playerc_bumper_t *device);
01015
01022 int playerc_bumper_get_geom(playerc_bumper_t *device);
01023
01024
01026
01027
01028
01029
01039 typedef struct
01040 {
01042 playerc_device_t info;
01043
01045 int width, height;
01046
01048 int bpp;
01049
01051 int format;
01052
01056 int fdiv;
01057
01059 int compression;
01060
01062 int image_count;
01063
01068 uint8_t image[PLAYER_CAMERA_IMAGE_SIZE];
01069
01070 } playerc_camera_t;
01071
01072
01074 playerc_camera_t *playerc_camera_create(playerc_client_t *client, int index);
01075
01077 void playerc_camera_destroy(playerc_camera_t *device);
01078
01080 int playerc_camera_subscribe(playerc_camera_t *device, int access);
01081
01083 int playerc_camera_unsubscribe(playerc_camera_t *device);
01084
01086 void playerc_camera_decompress(playerc_camera_t *device);
01087
01089 void playerc_camera_save(playerc_camera_t *device, const char *filename);
01090
01091
01092
01094
01095
01096
01097
01107 typedef struct
01108 {
01110 playerc_device_t info;
01111
01113 uint8_t count;
01114
01116 uint32_t digin;
01117
01118 } playerc_dio_t;
01119
01120
01122 playerc_dio_t *playerc_dio_create(playerc_client_t *client, int index);
01123
01125 void playerc_dio_destroy(playerc_dio_t *device);
01126
01128 int playerc_dio_subscribe(playerc_dio_t *device, int access);
01129
01131 int playerc_dio_unsubscribe(playerc_dio_t *device);
01132
01134 int playerc_dio_set_output(playerc_dio_t *device, uint8_t output_count, uint32_t digout);
01135
01136
01138
01139
01140
01141
01156 typedef struct
01157 {
01159 playerc_device_t info;
01160
01165 player_fiducial_geom_t fiducial_geom;
01166
01168 int fiducials_count;
01169 player_fiducial_item_t fiducials[PLAYERC_FIDUCIAL_MAX_SAMPLES];
01170
01171 } playerc_fiducial_t;
01172
01173
01175 playerc_fiducial_t *playerc_fiducial_create(playerc_client_t *client, int index);
01176
01178 void playerc_fiducial_destroy(playerc_fiducial_t *device);
01179
01181 int playerc_fiducial_subscribe(playerc_fiducial_t *device, int access);
01182
01184 int playerc_fiducial_unsubscribe(playerc_fiducial_t *device);
01185
01192 int playerc_fiducial_get_geom(playerc_fiducial_t *device);
01193
01194
01196
01197
01198
01207 typedef struct
01208 {
01210 playerc_device_t info;
01211
01213 double utc_time;
01214
01218 double lat, lon;
01219
01222 double alt;
01223
01225 double utm_e, utm_n;
01226
01228 double hdop;
01229
01231 double vdop;
01232
01234 double err_horz, err_vert;
01235
01237 int quality;
01238
01240 int sat_count;
01241
01242 } playerc_gps_t;
01243
01244
01246 playerc_gps_t *playerc_gps_create(playerc_client_t *client, int index);
01247
01249 void playerc_gps_destroy(playerc_gps_t *device);
01250
01252 int playerc_gps_subscribe(playerc_gps_t *device, int access);
01253
01255 int playerc_gps_unsubscribe(playerc_gps_t *device);
01256
01257
01259
01260
01261
01271 typedef struct
01272 {
01274 playerc_device_t info;
01275
01277 player_color_t color;
01278
01279 } playerc_graphics2d_t;
01280
01281
01283 playerc_graphics2d_t *playerc_graphics2d_create(playerc_client_t *client, int index);
01284
01286 void playerc_graphics2d_destroy(playerc_graphics2d_t *device);
01287
01289 int playerc_graphics2d_subscribe(playerc_graphics2d_t *device, int access);
01290
01292 int playerc_graphics2d_unsubscribe(playerc_graphics2d_t *device);
01293
01295 int playerc_graphics2d_setcolor(playerc_graphics2d_t *device,
01296 player_color_t col );
01297
01299 int playerc_graphics2d_draw_points(playerc_graphics2d_t *device,
01300 player_point_2d_t pts[],
01301 int count );
01302
01304 int playerc_graphics2d_draw_polyline(playerc_graphics2d_t *device,
01305 player_point_2d_t pts[],
01306 int count );
01307
01309 int playerc_graphics2d_draw_polygon(playerc_graphics2d_t *device,
01310 player_point_2d_t pts[],
01311 int count,
01312 int filled,
01313 player_color_t fill_color );
01314
01316 int playerc_graphics2d_clear(playerc_graphics2d_t *device );
01317
01318
01321
01331 typedef struct
01332 {
01334 playerc_device_t info;
01335
01337 player_color_t color;
01338
01339 } playerc_graphics3d_t;
01340
01341
01343 playerc_graphics3d_t *playerc_graphics3d_create(playerc_client_t *client, int index);
01344
01346 void playerc_graphics3d_destroy(playerc_graphics3d_t *device);
01347
01349 int playerc_graphics3d_subscribe(playerc_graphics3d_t *device, int access);
01350
01352 int playerc_graphics3d_unsubscribe(playerc_graphics3d_t *device);
01353
01355 int playerc_graphics3d_setcolor(playerc_graphics3d_t *device,
01356 player_color_t col );
01357
01359 int playerc_graphics3d_draw(playerc_graphics3d_t *device,
01360 player_graphics3d_draw_mode_t mode,
01361 player_point_3d_t pts[],
01362 int count );
01363
01365 int playerc_graphics3d_clear(playerc_graphics3d_t *device );
01366
01367
01370
01380 typedef struct
01381 {
01383 playerc_device_t info;
01384
01389 double pose[3];
01390 double size[2];
01391
01392 unsigned char state;
01393 unsigned char beams;
01394 int outer_break_beam;
01395 int inner_break_beam;
01396 int paddles_open;
01397 int paddles_closed;
01398 int paddles_moving;
01399 int gripper_error;
01400 int lift_up;
01401 int lift_down;
01402 int lift_moving;
01403 int lift_error;
01404
01405 } playerc_gripper_t;
01406
01407
01409 playerc_gripper_t *playerc_gripper_create(playerc_client_t *client, int index);
01410
01412 void playerc_gripper_destroy(playerc_gripper_t *device);
01413
01415 int playerc_gripper_subscribe(playerc_gripper_t *device, int access);
01416
01418 int playerc_gripper_unsubscribe(playerc_gripper_t *device);
01419
01421 int playerc_gripper_set_cmd(playerc_gripper_t *device, uint8_t cmd, uint8_t arg);
01422
01425 void playerc_gripper_printout( playerc_gripper_t *device, const char* prefix );
01426
01427
01429
01430
01431
01432
01433
01444 typedef struct
01445 {
01447 playerc_device_t info;
01448
01449
01450 player_ir_data_t ranges;
01451
01452
01453 player_ir_pose_t poses;
01454
01455 } playerc_ir_t;
01456
01457
01459 playerc_ir_t *playerc_ir_create(playerc_client_t *client, int index);
01460
01462 void playerc_ir_destroy(playerc_ir_t *device);
01463
01465 int playerc_ir_subscribe(playerc_ir_t *device, int access);
01466
01468 int playerc_ir_unsubscribe(playerc_ir_t *device);
01469
01476 int playerc_ir_get_geom(playerc_ir_t *device);
01477
01478
01480
01481
01482
01483
01484
01498 typedef struct
01499 {
01501 playerc_device_t info;
01502
01506 double pose[3];
01507 double size[2];
01508
01510 double robot_pose[3];
01511
01513 int intensity_on;
01514
01516 int scan_count;
01517
01519 double scan_start;
01520
01522 double scan_res;
01523
01525 double range_res;
01526
01528 double max_range;
01529
01531 double ranges[PLAYERC_LASER_MAX_SAMPLES];
01532
01534 double scan[PLAYERC_LASER_MAX_SAMPLES][2];
01535
01537 player_point_2d_t point[PLAYERC_LASER_MAX_SAMPLES];
01538
01542 int intensity[PLAYERC_LASER_MAX_SAMPLES];
01543
01545 int scan_id;
01546
01547 } playerc_laser_t;
01548
01549
01551 playerc_laser_t *playerc_laser_create(playerc_client_t *client, int index);
01552
01554 void playerc_laser_destroy(playerc_laser_t *device);
01555
01557 int playerc_laser_subscribe(playerc_laser_t *device, int access);
01558
01560 int playerc_laser_unsubscribe(playerc_laser_t *device);
01561
01581 int playerc_laser_set_config(playerc_laser_t *device,
01582 double min_angle, double max_angle,
01583 double resolution,
01584 double range_res,
01585 unsigned char intensity);
01586
01606 int playerc_laser_get_config(playerc_laser_t *device,
01607 double *min_angle,
01608 double *max_angle,
01609 double *resolution,
01610 double *range_res,
01611 unsigned char *intensity);
01612
01619 int playerc_laser_get_geom(playerc_laser_t *device);
01620
01623 void playerc_laser_printout( playerc_laser_t * device,
01624 const char* prefix );
01625
01627
01628
01629
01641 typedef struct
01642 {
01644 playerc_device_t info;
01645
01646 player_limb_data_t data;
01647 player_limb_geom_req_t geom;
01648 } playerc_limb_t;
01649
01651 playerc_limb_t *playerc_limb_create(playerc_client_t *client, int index);
01652
01654 void playerc_limb_destroy(playerc_limb_t *device);
01655
01657 int playerc_limb_subscribe(playerc_limb_t *device, int access);
01658
01660 int playerc_limb_unsubscribe(playerc_limb_t *device);
01661
01664 int playerc_limb_get_geom(playerc_limb_t *device);
01665
01667 int playerc_limb_home_cmd(playerc_limb_t *device);
01668
01670 int playerc_limb_stop_cmd(playerc_limb_t *device);
01671
01673 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);
01674
01677 int playerc_limb_setposition_cmd(playerc_limb_t *device, float pX, float pY, float pZ);
01678
01681 int playerc_limb_vecmove_cmd(playerc_limb_t *device, float x, float y, float z, float length);
01682
01686 int playerc_limb_power(playerc_limb_t *device, uint enable);
01687
01689 int playerc_limb_brakes(playerc_limb_t *device, uint enable);
01690
01692 int playerc_limb_speed_config(playerc_limb_t *device, float speed);
01693
01695
01696
01697
01698
01715 typedef struct playerc_localize_particle
01716 {
01717 double pose[3];
01718 double weight;
01719 } playerc_localize_particle_t;
01720
01721
01723 typedef struct
01724 {
01726 playerc_device_t info;
01727
01729 int map_size_x, map_size_y;
01730
01732 double map_scale;
01733
01735 int map_tile_x, map_tile_y;
01736
01738 int8_t *map_cells;
01739
01741 int pending_count;
01742
01744 double pending_time;
01745
01747 int hypoth_count;
01748 player_localize_hypoth_t hypoths[PLAYER_LOCALIZE_MAX_HYPOTHS];
01749
01750 double mean[3];
01751 double variance;
01752 int num_particles;
01753 playerc_localize_particle_t particles[PLAYER_LOCALIZE_PARTICLES_MAX];
01754
01755 } playerc_localize_t;
01756
01757
01759 playerc_localize_t *playerc_localize_create(playerc_client_t *client, int index);
01760
01762 void playerc_localize_destroy(playerc_localize_t *device);
01763
01765 int playerc_localize_subscribe(playerc_localize_t *device, int access);
01766
01768 int playerc_localize_unsubscribe(playerc_localize_t *device);
01769
01771 int playerc_localize_set_pose(playerc_localize_t *device, double pose[3], double cov[3]);
01772
01775 int playerc_localize_get_particles(playerc_localize_t *device);
01776
01778
01779
01780
01781
01791 typedef struct
01792 {
01794 playerc_device_t info;
01795
01798 int type;
01799
01802 int state;
01803 } playerc_log_t;
01804
01805
01807 playerc_log_t *playerc_log_create(playerc_client_t *client, int index);
01808
01810 void playerc_log_destroy(playerc_log_t *device);
01811
01813 int playerc_log_subscribe(playerc_log_t *device, int access);
01814
01816 int playerc_log_unsubscribe(playerc_log_t *device);
01817
01819 int playerc_log_set_write_state(playerc_log_t* device, int state);
01820
01822 int playerc_log_set_read_state(playerc_log_t* device, int state);
01823
01825 int playerc_log_set_read_rewind(playerc_log_t* device);
01826
01832 int playerc_log_get_state(playerc_log_t* device);
01833
01835 int playerc_log_set_filename(playerc_log_t* device, const char* fname);
01836
01837
01841
01851 typedef struct
01852 {
01854 playerc_device_t info;
01855
01857 double resolution;
01858
01860 int width, height;
01861
01863 double origin[2];
01864
01866 char* cells;
01867
01870 double vminx, vminy, vmaxx, vmaxy;
01871 int num_segments;
01872 player_segment_t* segments;
01873 } playerc_map_t;
01874
01875
01878 #define PLAYERC_MAP_INDEX(dev, i, j) ((dev->width) * (j) + (i))
01879
01881 playerc_map_t *playerc_map_create(playerc_client_t *client, int index);
01882
01884 void playerc_map_destroy(playerc_map_t *device);
01885
01887 int playerc_map_subscribe(playerc_map_t *device, int access);
01888
01890 int playerc_map_unsubscribe(playerc_map_t *device);
01891
01893 int playerc_map_get_map(playerc_map_t* device);
01894
01896 int playerc_map_get_vector(playerc_map_t* device);
01897
01899
01900
01901
01912 typedef struct
01913 {
01915 playerc_device_t info;
01916
01918 int data_count;
01919
01921 uint8_t data[PLAYER_OPAQUE_MAX_SIZE];
01922 } playerc_opaque_t;
01923
01925 playerc_opaque_t *playerc_opaque_create(playerc_client_t *client, int index);
01926
01928 void playerc_opaque_destroy(playerc_opaque_t *device);
01929
01931 int playerc_opaque_subscribe(playerc_opaque_t *device, int access);
01932
01934 int playerc_opaque_unsubscribe(playerc_opaque_t *device);
01935
01937 int playerc_opaque_cmd(playerc_opaque_t *device, player_opaque_data_t *data);
01938
01940
01941
01942
01943
01953 typedef struct
01954 {
01956 playerc_device_t info;
01957
01959 int path_valid;
01960
01962 int path_done;
01963
01965 double px, py, pa;
01966
01968 double gx, gy, ga;
01969
01971 double wx, wy, wa;
01972
01976 int curr_waypoint;
01977
01979 int waypoint_count;
01980
01983 double waypoints[PLAYER_PLANNER_MAX_WAYPOINTS][3];
01984
01985 } playerc_planner_t;
01986
01988 playerc_planner_t *playerc_planner_create(playerc_client_t *client, int index);
01989
01991 void playerc_planner_destroy(playerc_planner_t *device);
01992
01994 int playerc_planner_subscribe(playerc_planner_t *device, int access);
01995
01997 int playerc_planner_unsubscribe(playerc_planner_t *device);
01998
02000 int playerc_planner_set_cmd_pose(playerc_planner_t *device,
02001 double gx, double gy, double ga);
02002
02009 int playerc_planner_get_waypoints(playerc_planner_t *device);
02010
02016 int playerc_planner_enable(playerc_planner_t *device, int state);
02017
02019
02020
02021
02032 typedef struct
02033 {
02035 playerc_device_t info;
02036
02040 double pose[3];
02041 double size[2];
02042
02044 double pos;
02045
02047 double vel;
02048
02050 int stall;
02051
02063 int status;
02064
02065 } playerc_position1d_t;
02066
02068 playerc_position1d_t *playerc_position1d_create(playerc_client_t *client,
02069 int index);
02070
02072 void playerc_position1d_destroy(playerc_position1d_t *device);
02073
02075 int playerc_position1d_subscribe(playerc_position1d_t *device, int access);
02076
02078 int playerc_position1d_unsubscribe(playerc_position1d_t *device);
02079
02081 int playerc_position1d_enable(playerc_position1d_t *device, int enable);
02082
02085 int playerc_position1d_get_geom(playerc_position1d_t *device);
02086
02088 int playerc_position1d_set_cmd_vel(playerc_position1d_t *device,
02089 double vel, int state);
02090
02094 int playerc_position1d_set_cmd_pos(playerc_position1d_t *device,
02095 double pos, int state);
02096
02101 int playerc_position1d_set_cmd_pos_with_vel(playerc_position1d_t *device,
02102 double pos, double vel, int state);
02103
02105 int playerc_position1d_set_odom(playerc_position1d_t *device,
02106 double odom);
02107
02109
02110
02111
02112
02126 typedef struct
02127 {
02129 playerc_device_t info;
02130
02134 double pose[3];
02135 double size[2];
02136
02138 double px, py, pa;
02139
02141 double vx, vy, va;
02142
02144 int stall;
02145
02146 } playerc_position2d_t;
02147
02149 playerc_position2d_t *playerc_position2d_create(playerc_client_t *client,
02150 int index);
02151
02153 void playerc_position2d_destroy(playerc_position2d_t *device);
02154
02156 int playerc_position2d_subscribe(playerc_position2d_t *device, int access);
02157
02159 int playerc_position2d_unsubscribe(playerc_position2d_t *device);
02160
02162 int playerc_position2d_enable(playerc_position2d_t *device, int enable);
02163
02166 int playerc_position2d_get_geom(playerc_position2d_t *device);
02167
02172 int playerc_position2d_set_cmd_vel(playerc_position2d_t *device,
02173 double vx, double vy, double va, int state);
02174
02176 int playerc_position2d_set_cmd_pose_with_vel(playerc_position2d_t *device,
02177 player_pose_t pos,
02178 player_pose_t vel,
02179 int state);
02180
02183 int playerc_position2d_set_cmd_pose(playerc_position2d_t *device,
02184 double gx, double gy, double ga, int state);
02185
02187 int playerc_position2d_set_cmd_car(playerc_position2d_t *device,
02188 double vx, double a);
02189
02191 int playerc_position2d_set_odom(playerc_position2d_t *device,
02192 double ox, double oy, double oa);
02193
02195
02196
02197
02212 typedef struct
02213 {
02215 playerc_device_t info;
02216
02220 double pose[3];
02221 double size[2];
02222
02224 double pos_x, pos_y, pos_z;
02225
02227 double pos_roll, pos_pitch, pos_yaw;
02228
02230 double vel_x, vel_y, vel_z;
02231
02233 double vel_roll, vel_pitch, vel_yaw;
02234
02236 int stall;
02237
02238 } playerc_position3d_t;
02239
02240
02242 playerc_position3d_t *playerc_position3d_create(playerc_client_t *client,
02243 int index);
02244
02246 void playerc_position3d_destroy(playerc_position3d_t *device);
02247
02249 int playerc_position3d_subscribe(playerc_position3d_t *device, int access);
02250
02252 int playerc_position3d_unsubscribe(playerc_position3d_t *device);
02253
02255 int playerc_position3d_enable(playerc_position3d_t *device, int enable);
02256
02259 int playerc_position3d_get_geom(playerc_position3d_t *device);
02260
02265 int playerc_position3d_set_velocity(playerc_position3d_t *device,
02266 double vx, double vy, double vz,
02267 double vr, double vp, double vt,
02268 int state);
02269
02271 int playerc_position3d_set_speed(playerc_position3d_t *device,
02272 double vx, double vy, double vz, int state);
02273
02276 int playerc_position3d_set_pose(playerc_position3d_t *device,
02277 double gx, double gy, double gz,
02278 double gr, double gp, double gt);
02279
02280
02282 int playerc_position3d_set_pose_with_vel(playerc_position3d_t *device,
02283 player_pose3d_t pos,
02284 player_pose3d_t vel);
02285
02287 int playerc_position3d_set_cmd_pose(playerc_position3d_t *device,
02288 double gx, double gy, double gz);
02289
02291 int playerc_position3d_set_vel_mode(playerc_position3d_t *device, int mode);
02292
02294 int playerc_position3d_set_odom(playerc_position3d_t *device,
02295 double ox, double oy, double oz,
02296 double oroll, double opitch, double oyaw);
02297
02299 int playerc_position3d_reset_odom(playerc_position3d_t *device);
02300
02302
02303
02304
02305
02316 typedef struct
02317 {
02319 playerc_device_t info;
02320
02323 int valid;
02324
02326 double charge;
02327
02329 double percent;
02330
02332 double joules;
02333
02336 double watts;
02337
02339 int charging;
02340
02341 } playerc_power_t;
02342
02343
02345 playerc_power_t *playerc_power_create(playerc_client_t *client, int index);
02346
02348 void playerc_power_destroy(playerc_power_t *device);
02349
02351 int playerc_power_subscribe(playerc_power_t *device, int access);
02352
02354 int playerc_power_unsubscribe(playerc_power_t *device);
02355
02356
02358
02359
02360
02361
02362
02373 typedef struct
02374 {
02376 playerc_device_t info;
02377
02381 double pan, tilt;
02382
02384 double zoom;
02385
02386 } playerc_ptz_t;
02387
02388
02390 playerc_ptz_t *playerc_ptz_create(playerc_client_t *client, int index);
02391
02393 void playerc_ptz_destroy(playerc_ptz_t *device);
02394
02396 int playerc_ptz_subscribe(playerc_ptz_t *device, int access);
02397
02399 int playerc_ptz_unsubscribe(playerc_ptz_t *device);
02400
02409 int playerc_ptz_set(playerc_ptz_t *device, double pan, double tilt, double zoom);
02410
02421 int playerc_ptz_set_ws(playerc_ptz_t *device, double pan, double tilt, double zoom,
02422 double panspeed, double tiltspeed);
02423
02431 int playerc_ptz_set_control_mode(playerc_ptz_t *device, int mode);
02432
02434
02435
02436
02447 typedef struct
02448 {
02450 playerc_device_t info;
02451
02453 int pose_count;
02454
02457 player_pose_t poses[PLAYERC_SONAR_MAX_SAMPLES];
02458
02460 int scan_count;
02461
02463 double scan[PLAYERC_SONAR_MAX_SAMPLES];
02464
02465 } playerc_sonar_t;
02466
02467
02469 playerc_sonar_t *playerc_sonar_create(playerc_client_t *client, int index);
02470
02472 void playerc_sonar_destroy(playerc_sonar_t *device);
02473
02475 int playerc_sonar_subscribe(playerc_sonar_t *device, int access);
02476
02478 int playerc_sonar_unsubscribe(playerc_sonar_t *device);
02479
02485 int playerc_sonar_get_geom(playerc_sonar_t *device);
02486
02488
02489
02490
02502 typedef struct
02503 {
02505 char mac[32];
02506
02508 char ip[32];
02509
02511 char essid[32];
02512
02514 int mode;
02515
02517 int encrypt;
02518
02520 double freq;
02521
02523 int qual, level, noise;
02524
02525 } playerc_wifi_link_t;
02526
02527
02529 typedef struct
02530 {
02532 playerc_device_t info;
02533
02535 playerc_wifi_link_t links[PLAYERC_WIFI_MAX_LINKS];
02536 int link_count;
02537
02538 } playerc_wifi_t;
02539
02540
02542 playerc_wifi_t *playerc_wifi_create(playerc_client_t *client, int index);
02543
02545 void playerc_wifi_destroy(playerc_wifi_t *device);
02546
02548 int playerc_wifi_subscribe(playerc_wifi_t *device, int access);
02549
02551 int playerc_wifi_unsubscribe(playerc_wifi_t *device);
02552
02554 playerc_wifi_link_t *playerc_wifi_get_link(playerc_wifi_t *device, int link);
02555
02556
02558
02559
02560
02572 typedef struct
02573 {
02575 playerc_device_t info;
02576
02577 } playerc_simulation_t;
02578
02579
02581 playerc_simulation_t *playerc_simulation_create(playerc_client_t *client, int index);
02582
02584 void playerc_simulation_destroy(playerc_simulation_t *device);
02585
02587 int playerc_simulation_subscribe(playerc_simulation_t *device, int access);
02588
02590 int playerc_simulation_unsubscribe(playerc_simulation_t *device);
02591
02593 int playerc_simulation_set_pose2d(playerc_simulation_t *device, char* name,
02594 double gx, double gy, double ga);
02595
02597 int playerc_simulation_get_pose2d(playerc_simulation_t *device, char* identifier,
02598 double *x, double *y, double *a);
02599
02602 int playerc_simulation_set_property_int(playerc_simulation_t *device,
02603 char* name,
02604 char* property,
02605 int value );
02608 int playerc_simulation_set_property_double(playerc_simulation_t *device,
02609 char* name,
02610 char* property,
02611 double value );
02614 int playerc_simulation_set_property_string(playerc_simulation_t *device,
02615 char* name,
02616 char* property,
02617 char* value );
02619
02620
02621
02622
02632 typedef struct
02633 {
02635 playerc_device_t info;
02636 } playerc_speech_t;
02637
02638
02640 playerc_speech_t *playerc_speech_create(playerc_client_t *client, int index);
02641
02643 void playerc_speech_destroy(playerc_speech_t *device);
02644
02646 int playerc_speech_subscribe(playerc_speech_t *device, int access);
02647
02649 int playerc_speech_unsubscribe(playerc_speech_t *device);
02650
02652 int playerc_speech_say (playerc_speech_t *device, const char *);
02653
02654
02656
02657
02658
02668 typedef struct
02669 {
02671 playerc_device_t info;
02672
02673 char rawText[PLAYER_SPEECH_RECOGNITION_TEXT_LEN];
02674
02675
02676 char words[20][30];
02677 int wordCount;
02678 } playerc_speechrecognition_t;
02679
02680
02682 playerc_speechrecognition_t *playerc_speechrecognition_create(playerc_client_t *client, int index);
02683
02685 void playerc_speechrecognition_destroy(playerc_speechrecognition_t *device);
02686
02688 int playerc_speechrecognition_subscribe(playerc_speechrecognition_t *device, int access);
02689
02691 int playerc_speechrecognition_unsubscribe(playerc_speechrecognition_t *device);
02692
02694
02695
02696
02706 typedef struct
02707 {
02709 uint32_t type;
02711 uint32_t guid_count;
02713 uint8_t guid[PLAYERC_RFID_MAX_GUID];
02714 } playerc_rfidtag_t;
02715
02717 typedef struct
02718 {
02720 playerc_device_t info;
02721
02723 uint16_t tags_count;
02724
02726 playerc_rfidtag_t tags[PLAYERC_RFID_MAX_TAGS];
02727 } playerc_rfid_t;
02728
02729
02731 playerc_rfid_t *playerc_rfid_create(playerc_client_t *client, int index);
02732
02734 void playerc_rfid_destroy(playerc_rfid_t *device);
02735
02737 int playerc_rfid_subscribe(playerc_rfid_t *device, int access);
02738
02740 int playerc_rfid_unsubscribe(playerc_rfid_t *device);
02741
02743
02744
02745
02758 typedef struct
02759 {
02761 playerc_device_t info;
02762
02764 uint32_t node_type;
02766 uint32_t node_id;
02768 uint32_t node_parent_id;
02770 player_wsn_node_data_t data_packet;
02771 } playerc_wsn_t;
02772
02773
02775 playerc_wsn_t *playerc_wsn_create(playerc_client_t *client, int index);
02776
02778 void playerc_wsn_destroy(playerc_wsn_t *device);
02779
02781 int playerc_wsn_subscribe(playerc_wsn_t *device, int access);
02782
02784 int playerc_wsn_unsubscribe(playerc_wsn_t *device);
02785
02787 int playerc_wsn_set_devstate(playerc_wsn_t *device, int node_id,
02788 int group_id, int devnr, int state);
02789
02791 int playerc_wsn_power(playerc_wsn_t *device, int node_id, int group_id,
02792 int value);
02793
02795 int playerc_wsn_datatype(playerc_wsn_t *device, int value);
02796
02798 int playerc_wsn_datafreq(playerc_wsn_t *device, int node_id, int group_id,
02799 double frequency);
02800
02802
02803
02804 #ifdef __cplusplus
02805 }
02806 #endif
02807
02808 #endif