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
00044 #ifndef PLAYERC_H
00045 #define PLAYERC_H
00046
00047 #include <stdio.h>
00048
00049
00050 #include <libplayercore/player.h>
00051 #include <libplayercore/playercommon.h>
00052 #include <libplayercore/error.h>
00053 #include <libplayerxdr/playerxdr.h>
00054
00055 #ifndef MIN
00056 #define MIN(a,b) ((a < b) ? a : b)
00057 #endif
00058 #ifndef MAX
00059 #define MAX(a,b) ((a > b) ? a : b)
00060 #endif
00061
00062 #ifdef __cplusplus
00063 extern "C" {
00064 #endif
00065
00066
00067
00068
00069
00070
00072 #define PLAYERC_OPEN_MODE PLAYER_OPEN_MODE
00073 #define PLAYERC_CLOSE_MODE PLAYER_CLOSE_MODE
00074 #define PLAYERC_ERROR_MODE PLAYER_ERROR_MODE
00075
00076
00078
00079
00080
00081
00082
00083 #define PLAYERC_DATAMODE_PUSH PLAYER_DATAMODE_PUSH
00084 #define PLAYERC_DATAMODE_PULL PLAYER_DATAMODE_PULL
00085
00086
00087
00088
00089
00090
00091
00092 #define PLAYERC_MAX_DEVICES PLAYER_MAX_DEVICES
00093 #define PLAYERC_LASER_MAX_SAMPLES PLAYER_LASER_MAX_SAMPLES
00094 #define PLAYERC_FIDUCIAL_MAX_SAMPLES PLAYER_FIDUCIAL_MAX_SAMPLES
00095 #define PLAYERC_SONAR_MAX_SAMPLES PLAYER_SONAR_MAX_SAMPLES
00096 #define PLAYERC_BUMPER_MAX_SAMPLES PLAYER_BUMPER_MAX_SAMPLES
00097 #define PLAYERC_IR_MAX_SAMPLES PLAYER_IR_MAX_SAMPLES
00098 #define PLAYERC_BLOBFINDER_MAX_BLOBS PLAYER_BLOBFINDER_MAX_BLOBS
00099 #define PLAYERC_WIFI_MAX_LINKS PLAYER_WIFI_MAX_LINKS
00100 #define PLAYERC_RFID_MAX_TAGS PLAYER_RFID_MAX_TAGS
00101 #define PLAYERC_RFID_MAX_GUID PLAYER_RFID_MAX_GUID
00102
00232
00238
00239
00244 const char *playerc_error_str(void);
00245
00247 const char *playerc_lookup_name(int code);
00248
00250 int playerc_lookup_code(const char *name);
00251
00253
00254
00255
00256
00257 struct _playerc_client_t;
00258 struct _playerc_device_t;
00259
00260
00261
00262
00263 struct pollfd;
00264
00265
00266
00277
00278 typedef struct
00279 {
00280 player_msghdr_t header;
00281 void *data;
00282 } playerc_client_item_t;
00283
00284
00285
00286 typedef struct
00287 {
00288
00289 int client_count;
00290 struct _playerc_client_t *client[128];
00291
00292
00293 struct pollfd* pollfd;
00294
00295
00296 double time;
00297
00298 } playerc_mclient_t;
00299
00300
00301 playerc_mclient_t *playerc_mclient_create(void);
00302
00303
00304 void playerc_mclient_destroy(playerc_mclient_t *mclient);
00305
00306
00307 int playerc_mclient_addclient(playerc_mclient_t *mclient, struct _playerc_client_t *client);
00308
00309
00310
00311 int playerc_mclient_peek(playerc_mclient_t *mclient, int timeout);
00312
00313
00314
00315 int playerc_mclient_read(playerc_mclient_t *mclient, int timeout);
00316
00318
00319
00320
00321
00334 typedef void (*playerc_putmsg_fn_t) (void *device, char *header, char *data);
00335
00337 typedef void (*playerc_callback_fn_t) (void *data);
00338
00339
00343 typedef struct
00344 {
00346 player_devaddr_t addr;
00347
00349 char drivername[PLAYER_MAX_DRIVER_STRING_LEN];
00350
00351 } playerc_device_info_t;
00352
00353
00355 typedef struct _playerc_client_t
00356 {
00359 void *id;
00360
00362 char *host;
00363 int port;
00364
00366 int sock;
00367
00369 uint8_t mode;
00370
00373 playerc_device_info_t devinfos[PLAYERC_MAX_DEVICES];
00374 int devinfo_count;
00375
00377 struct _playerc_device_t *device[32];
00378 int device_count;
00379
00381 playerc_client_item_t qitems[512];
00382 int qfirst, qlen, qsize;
00383
00385 char *data;
00386 char *xdrdata;
00387
00389 double datatime;
00391 double lasttime;
00392
00393 } playerc_client_t;
00394
00395
00411 playerc_client_t *playerc_client_create(playerc_mclient_t *mclient,
00412 const char *host, int port);
00413
00419 void playerc_client_destroy(playerc_client_t *client);
00420
00429 int playerc_client_connect(playerc_client_t *client);
00430
00439 int playerc_client_disconnect(playerc_client_t *client);
00440
00453 int playerc_client_datamode(playerc_client_t *client, uint8_t mode);
00454
00466 int playerc_client_requestdata(playerc_client_t* client);
00467
00479
00480
00503 int playerc_client_set_replace_rule(playerc_client_t *client, int interf, int index, int type, int subtype, int replace);
00504
00505
00508 int playerc_client_adddevice(playerc_client_t *client, struct _playerc_device_t *device);
00509
00510
00513 int playerc_client_deldevice(playerc_client_t *client, struct _playerc_device_t *device);
00514
00517 int playerc_client_addcallback(playerc_client_t *client, struct _playerc_device_t *device,
00518 playerc_callback_fn_t callback, void *data);
00519
00522 int playerc_client_delcallback(playerc_client_t *client, struct _playerc_device_t *device,
00523 playerc_callback_fn_t callback, void *data);
00524
00536 int playerc_client_get_devlist(playerc_client_t *client);
00537
00540 int playerc_client_subscribe(playerc_client_t *client, int code, int index,
00541 int access, char *drivername, size_t len);
00542
00545 int playerc_client_unsubscribe(playerc_client_t *client, int code, int index);
00546
00552 int playerc_client_request(playerc_client_t *client,
00553 struct _playerc_device_t *device, uint8_t reqtype,
00554 void *req_data, void *rep_data, int rep_len);
00555
00566
00567
00568
00579 int playerc_client_peek(playerc_client_t *client, int timeout);
00580
00591 void *playerc_client_read(playerc_client_t *client);
00592
00593
00594
00597 int playerc_client_write(playerc_client_t *client,
00598 struct _playerc_device_t *device,
00599 uint8_t subtype,
00600 void *cmd, double* timestamp);
00601
00602
00604
00605
00606
00607
00620 typedef struct _playerc_device_t
00621 {
00625 void *id;
00626
00628 playerc_client_t *client;
00629
00631 player_devaddr_t addr;
00632
00634 char drivername[PLAYER_MAX_DRIVER_STRING_LEN];
00635
00638 int subscribed;
00639
00641 double datatime;
00642
00644 double lasttime;
00645
00649 int fresh;
00653 int freshgeom;
00657 int freshconfig;
00658
00660 playerc_putmsg_fn_t putmsg;
00661
00663 void *user_data;
00664
00666 int callback_count;
00667 playerc_callback_fn_t callback[4];
00668 void *callback_data[4];
00669
00670 } playerc_device_t;
00671
00672
00674 void playerc_device_init(playerc_device_t *device, playerc_client_t *client,
00675 int code, int index, playerc_putmsg_fn_t putmsg);
00676
00678 void playerc_device_term(playerc_device_t *device);
00679
00681 int playerc_device_subscribe(playerc_device_t *device, int access);
00682
00684 int playerc_device_unsubscribe(playerc_device_t *device);
00685
00687
00688
00689
00690
00695
00696
00697
00707 typedef struct
00708 {
00710 playerc_device_t info;
00711
00713 uint8_t voltages_count;
00714
00716 float voltages[PLAYER_AIO_MAX_INPUTS];
00717
00718 } playerc_aio_t;
00719
00720
00722 playerc_aio_t *playerc_aio_create(playerc_client_t *client, int index);
00723
00725 void playerc_aio_destroy(playerc_aio_t *device);
00726
00728 int playerc_aio_subscribe(playerc_aio_t *device, int access);
00729
00731 int playerc_aio_unsubscribe(playerc_aio_t *device);
00732
00734 int playerc_aio_set_output(playerc_aio_t *device, uint8_t id, float volt);
00735
00737
00738
00739
00740
00752 typedef struct
00753 {
00755 playerc_device_t info;
00756
00758 uint32_t actuators_count;
00760 player_actarray_actuator_t actuators_data[PLAYER_ACTARRAY_NUM_ACTUATORS];
00761 player_actarray_actuatorgeom_t actuators_geom[PLAYER_ACTARRAY_NUM_ACTUATORS];
00762 } playerc_actarray_t;
00763
00765 playerc_actarray_t *playerc_actarray_create(playerc_client_t *client, int index);
00766
00768 void playerc_actarray_destroy(playerc_actarray_t *device);
00769
00771 int playerc_actarray_subscribe(playerc_actarray_t *device, int access);
00772
00774 int playerc_actarray_unsubscribe(playerc_actarray_t *device);
00775
00778 int playerc_actarray_get_geom(playerc_actarray_t *device);
00779
00781 int playerc_actarray_position_cmd(playerc_actarray_t *device, int joint, float position);
00782
00784 int playerc_actarray_speed_cmd(playerc_actarray_t *device, int joint, float speed);
00785
00787 int playerc_actarray_home_cmd(playerc_actarray_t *device, int joint);
00788
00792 int playerc_actarray_power(playerc_actarray_t *device, uint8_t enable);
00793
00795 int playerc_actarray_brakes(playerc_actarray_t *device, uint8_t enable);
00796
00798 int playerc_actarray_speed_config(playerc_actarray_t *device, int joint, float speed);
00799
00801
00802
00803
00804
00816 typedef struct
00817 {
00819 unsigned int id;
00820
00823 uint32_t color;
00824
00826 unsigned int x, y;
00827
00829 unsigned int left, top, right, bottom;
00830
00832 unsigned int area;
00833
00835 double range;
00836
00837 } playerc_blobfinder_blob_t;
00838
00839
00841 typedef struct
00842 {
00844 playerc_device_t info;
00845
00847 unsigned int width, height;
00848
00850 unsigned int blobs_count;
00851 playerc_blobfinder_blob_t blobs[PLAYERC_BLOBFINDER_MAX_BLOBS];
00852
00853 } playerc_blobfinder_t;
00854
00855
00857 playerc_blobfinder_t *playerc_blobfinder_create(playerc_client_t *client, int index);
00858
00860 void playerc_blobfinder_destroy(playerc_blobfinder_t *device);
00861
00863 int playerc_blobfinder_subscribe(playerc_blobfinder_t *device, int access);
00864
00866 int playerc_blobfinder_unsubscribe(playerc_blobfinder_t *device);
00867
00868
00870
00871
00872
00873
00884 typedef struct
00885 {
00887 playerc_device_t info;
00888
00890 int pose_count;
00891
00895 player_bumper_define_t poses[PLAYERC_BUMPER_MAX_SAMPLES];
00896
00898 int bumper_count;
00899
00901 uint8_t bumpers[PLAYERC_BUMPER_MAX_SAMPLES];
00902
00903 } playerc_bumper_t;
00904
00905
00907 playerc_bumper_t *playerc_bumper_create(playerc_client_t *client, int index);
00908
00910 void playerc_bumper_destroy(playerc_bumper_t *device);
00911
00913 int playerc_bumper_subscribe(playerc_bumper_t *device, int access);
00914
00916 int playerc_bumper_unsubscribe(playerc_bumper_t *device);
00917
00924 int playerc_bumper_get_geom(playerc_bumper_t *device);
00925
00926
00928
00929
00930
00931
00941 typedef struct
00942 {
00944 playerc_device_t info;
00945
00947 int width, height;
00948
00950 int bpp;
00951
00953 int format;
00954
00958 int fdiv;
00959
00961 int compression;
00962
00964 int image_count;
00965
00970 uint8_t image[PLAYER_CAMERA_IMAGE_SIZE];
00971
00972 } playerc_camera_t;
00973
00974
00976 playerc_camera_t *playerc_camera_create(playerc_client_t *client, int index);
00977
00979 void playerc_camera_destroy(playerc_camera_t *device);
00980
00982 int playerc_camera_subscribe(playerc_camera_t *device, int access);
00983
00985 int playerc_camera_unsubscribe(playerc_camera_t *device);
00986
00988 void playerc_camera_decompress(playerc_camera_t *device);
00989
00991 void playerc_camera_save(playerc_camera_t *device, const char *filename);
00992
00993
00994
00996
00997
00998
01013 typedef struct
01014 {
01016 playerc_device_t info;
01017
01022 player_fiducial_geom_t fiducial_geom;
01023
01025 int fiducials_count;
01026 player_fiducial_item_t fiducials[PLAYERC_FIDUCIAL_MAX_SAMPLES];
01027
01028 } playerc_fiducial_t;
01029
01030
01032 playerc_fiducial_t *playerc_fiducial_create(playerc_client_t *client, int index);
01033
01035 void playerc_fiducial_destroy(playerc_fiducial_t *device);
01036
01038 int playerc_fiducial_subscribe(playerc_fiducial_t *device, int access);
01039
01041 int playerc_fiducial_unsubscribe(playerc_fiducial_t *device);
01042
01049 int playerc_fiducial_get_geom(playerc_fiducial_t *device);
01050
01051
01053
01054
01055
01064 typedef struct
01065 {
01067 playerc_device_t info;
01068
01070 double utc_time;
01071
01075 double lat, lon;
01076
01079 double alt;
01080
01082 double utm_e, utm_n;
01083
01085 double hdop;
01086
01088 double vdop;
01089
01091 double err_horz, err_vert;
01092
01094 int quality;
01095
01097 int sat_count;
01098
01099 } playerc_gps_t;
01100
01101
01103 playerc_gps_t *playerc_gps_create(playerc_client_t *client, int index);
01104
01106 void playerc_gps_destroy(playerc_gps_t *device);
01107
01109 int playerc_gps_subscribe(playerc_gps_t *device, int access);
01110
01112 int playerc_gps_unsubscribe(playerc_gps_t *device);
01113
01114
01116
01117
01118
01128 typedef struct
01129 {
01131 playerc_device_t info;
01132
01134 player_color_t color;
01135
01136 } playerc_graphics2d_t;
01137
01138
01140 playerc_graphics2d_t *playerc_graphics2d_create(playerc_client_t *client, int index);
01141
01143 void playerc_graphics2d_destroy(playerc_graphics2d_t *device);
01144
01146 int playerc_graphics2d_subscribe(playerc_graphics2d_t *device, int access);
01147
01149 int playerc_graphics2d_unsubscribe(playerc_graphics2d_t *device);
01150
01152 int playerc_graphics2d_setcolor(playerc_graphics2d_t *device,
01153 player_color_t col );
01154
01156 int playerc_graphics2d_draw_points(playerc_graphics2d_t *device,
01157 player_point_2d_t pts[],
01158 int count );
01159
01161 int playerc_graphics2d_draw_polyline(playerc_graphics2d_t *device,
01162 player_point_2d_t pts[],
01163 int count );
01164
01166 int playerc_graphics2d_draw_polygon(playerc_graphics2d_t *device,
01167 player_point_2d_t pts[],
01168 int count,
01169 int filled,
01170 player_color_t fill_color );
01171
01173 int playerc_graphics2d_clear(playerc_graphics2d_t *device );
01174
01175
01178
01188 typedef struct
01189 {
01191 playerc_device_t info;
01192
01197 double pose[3];
01198 double size[2];
01199
01200 unsigned char state;
01201 unsigned char beams;
01202 int outer_break_beam;
01203 int inner_break_beam;
01204 int paddles_open;
01205 int paddles_closed;
01206 int paddles_moving;
01207 int gripper_error;
01208 int lift_up;
01209 int lift_down;
01210 int lift_moving;
01211 int lift_error;
01212
01213 } playerc_gripper_t;
01214
01215
01217 playerc_gripper_t *playerc_gripper_create(playerc_client_t *client, int index);
01218
01220 void playerc_gripper_destroy(playerc_gripper_t *device);
01221
01223 int playerc_gripper_subscribe(playerc_gripper_t *device, int access);
01224
01226 int playerc_gripper_unsubscribe(playerc_gripper_t *device);
01227
01229 int playerc_gripper_set_cmd(playerc_gripper_t *device, uint8_t cmd, uint8_t arg);
01230
01233 void playerc_gripper_printout( playerc_gripper_t *device, const char* prefix );
01234
01235
01237
01238
01239
01240
01241
01252 typedef struct
01253 {
01255 playerc_device_t info;
01256
01257
01258 player_ir_data_t ranges;
01259
01260
01261 player_ir_pose_t poses;
01262
01263 } playerc_ir_t;
01264
01265
01267 playerc_ir_t *playerc_ir_create(playerc_client_t *client, int index);
01268
01270 void playerc_ir_destroy(playerc_ir_t *device);
01271
01273 int playerc_ir_subscribe(playerc_ir_t *device, int access);
01274
01276 int playerc_ir_unsubscribe(playerc_ir_t *device);
01277
01284 int playerc_ir_get_geom(playerc_ir_t *device);
01285
01286
01288
01289
01290
01291
01292
01306 typedef struct
01307 {
01309 playerc_device_t info;
01310
01314 double pose[3];
01315 double size[2];
01316
01318 double robot_pose[3];
01319
01321 int intensity_on;
01322
01324 int scan_count;
01325
01327 double scan_start;
01328
01330 double scan_res;
01331
01333 double range_res;
01334
01336 double max_range;
01337
01339 double ranges[PLAYERC_LASER_MAX_SAMPLES];
01340
01342 double scan[PLAYERC_LASER_MAX_SAMPLES][2];
01343
01345 player_point_2d_t point[PLAYERC_LASER_MAX_SAMPLES];
01346
01350 int intensity[PLAYERC_LASER_MAX_SAMPLES];
01351
01353 int scan_id;
01354
01355 } playerc_laser_t;
01356
01357
01359 playerc_laser_t *playerc_laser_create(playerc_client_t *client, int index);
01360
01362 void playerc_laser_destroy(playerc_laser_t *device);
01363
01365 int playerc_laser_subscribe(playerc_laser_t *device, int access);
01366
01368 int playerc_laser_unsubscribe(playerc_laser_t *device);
01369
01389 int playerc_laser_set_config(playerc_laser_t *device,
01390 double min_angle, double max_angle,
01391 double resolution,
01392 double range_res,
01393 unsigned char intensity);
01394
01414 int playerc_laser_get_config(playerc_laser_t *device,
01415 double *min_angle,
01416 double *max_angle,
01417 double *resolution,
01418 double *range_res,
01419 unsigned char *intensity);
01420
01427 int playerc_laser_get_geom(playerc_laser_t *device);
01428
01431 void playerc_laser_printout( playerc_laser_t * device,
01432 const char* prefix );
01433
01435
01436
01437
01449 typedef struct
01450 {
01452 playerc_device_t info;
01453
01454 player_limb_data_t data;
01455 player_limb_geom_req_t geom;
01456 } playerc_limb_t;
01457
01459 playerc_limb_t *playerc_limb_create(playerc_client_t *client, int index);
01460
01462 void playerc_limb_destroy(playerc_limb_t *device);
01463
01465 int playerc_limb_subscribe(playerc_limb_t *device, int access);
01466
01468 int playerc_limb_unsubscribe(playerc_limb_t *device);
01469
01472 int playerc_limb_get_geom(playerc_limb_t *device);
01473
01475 int playerc_limb_home_cmd(playerc_limb_t *device);
01476
01478 int playerc_limb_stop_cmd(playerc_limb_t *device);
01479
01481 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);
01482
01485 int playerc_limb_setposition_cmd(playerc_limb_t *device, float pX, float pY, float pZ);
01486
01489 int playerc_limb_vecmove_cmd(playerc_limb_t *device, float x, float y, float z, float length);
01490
01494 int playerc_limb_power(playerc_limb_t *device, uint enable);
01495
01497 int playerc_limb_brakes(playerc_limb_t *device, uint enable);
01498
01500 int playerc_limb_speed_config(playerc_limb_t *device, float speed);
01501
01503
01504
01505
01506
01523 typedef struct playerc_localize_particle
01524 {
01525 double pose[3];
01526 double weight;
01527 } playerc_localize_particle_t;
01528
01529
01531 typedef struct
01532 {
01534 playerc_device_t info;
01535
01537 int map_size_x, map_size_y;
01538
01540 double map_scale;
01541
01543 int map_tile_x, map_tile_y;
01544
01546 int8_t *map_cells;
01547
01549 int pending_count;
01550
01552 double pending_time;
01553
01555 int hypoth_count;
01556 player_localize_hypoth_t hypoths[PLAYER_LOCALIZE_MAX_HYPOTHS];
01557
01558 double mean[3];
01559 double variance;
01560 int num_particles;
01561 playerc_localize_particle_t particles[PLAYER_LOCALIZE_PARTICLES_MAX];
01562
01563 } playerc_localize_t;
01564
01565
01567 playerc_localize_t *playerc_localize_create(playerc_client_t *client, int index);
01568
01570 void playerc_localize_destroy(playerc_localize_t *device);
01571
01573 int playerc_localize_subscribe(playerc_localize_t *device, int access);
01574
01576 int playerc_localize_unsubscribe(playerc_localize_t *device);
01577
01579 int playerc_localize_set_pose(playerc_localize_t *device, double pose[3], double cov[3]);
01580
01581
01582
01583 int playerc_localize_get_particles(playerc_localize_t *device);
01584
01586
01587
01588
01589
01599 typedef struct
01600 {
01602 playerc_device_t info;
01603
01606 int type;
01607
01610 int state;
01611 } playerc_log_t;
01612
01613
01615 playerc_log_t *playerc_log_create(playerc_client_t *client, int index);
01616
01618 void playerc_log_destroy(playerc_log_t *device);
01619
01621 int playerc_log_subscribe(playerc_log_t *device, int access);
01622
01624 int playerc_log_unsubscribe(playerc_log_t *device);
01625
01627 int playerc_log_set_write_state(playerc_log_t* device, int state);
01628
01630 int playerc_log_set_read_state(playerc_log_t* device, int state);
01631
01633 int playerc_log_set_read_rewind(playerc_log_t* device);
01634
01640 int playerc_log_get_state(playerc_log_t* device);
01641
01643 int playerc_log_set_filename(playerc_log_t* device, const char* fname);
01644
01645
01649
01659 typedef struct
01660 {
01662 playerc_device_t info;
01663
01665 double resolution;
01666
01668 int width, height;
01669
01671 double origin[2];
01672
01674 char* cells;
01675
01678 double vminx, vminy, vmaxx, vmaxy;
01679 int num_segments;
01680 player_segment_t* segments;
01681 } playerc_map_t;
01682
01683
01686 #define PLAYERC_MAP_INDEX(dev, i, j) ((dev->width) * (j) + (i))
01687
01689 playerc_map_t *playerc_map_create(playerc_client_t *client, int index);
01690
01692 void playerc_map_destroy(playerc_map_t *device);
01693
01695 int playerc_map_subscribe(playerc_map_t *device, int access);
01696
01698 int playerc_map_unsubscribe(playerc_map_t *device);
01699
01701 int playerc_map_get_map(playerc_map_t* device);
01702
01704 int playerc_map_get_vector(playerc_map_t* device);
01705
01707
01708
01709
01719 typedef struct
01720 {
01722 playerc_device_t info;
01723
01725 int path_valid;
01726
01728 int path_done;
01729
01731 double px, py, pa;
01732
01734 double gx, gy, ga;
01735
01737 double wx, wy, wa;
01738
01742 int curr_waypoint;
01743
01745 int waypoint_count;
01746
01749 double waypoints[PLAYER_PLANNER_MAX_WAYPOINTS][3];
01750
01751 } playerc_planner_t;
01752
01754 playerc_planner_t *playerc_planner_create(playerc_client_t *client, int index);
01755
01757 void playerc_planner_destroy(playerc_planner_t *device);
01758
01760 int playerc_planner_subscribe(playerc_planner_t *device, int access);
01761
01763 int playerc_planner_unsubscribe(playerc_planner_t *device);
01764
01766 int playerc_planner_set_cmd_pose(playerc_planner_t *device,
01767 double gx, double gy, double ga);
01768
01775 int playerc_planner_get_waypoints(playerc_planner_t *device);
01776
01782 int playerc_planner_enable(playerc_planner_t *device, int state);
01783
01785
01786
01787
01788
01802 typedef struct
01803 {
01805 playerc_device_t info;
01806
01810 double pose[3];
01811 double size[2];
01812
01814 double px, py, pa;
01815
01817 double vx, vy, va;
01818
01820 int stall;
01821
01822 } playerc_position2d_t;
01823
01825 playerc_position2d_t *playerc_position2d_create(playerc_client_t *client,
01826 int index);
01827
01829 void playerc_position2d_destroy(playerc_position2d_t *device);
01830
01832 int playerc_position2d_subscribe(playerc_position2d_t *device, int access);
01833
01835 int playerc_position2d_unsubscribe(playerc_position2d_t *device);
01836
01838 int playerc_position2d_enable(playerc_position2d_t *device, int enable);
01839
01842 int playerc_position2d_get_geom(playerc_position2d_t *device);
01843
01848 int playerc_position2d_set_cmd_vel(playerc_position2d_t *device,
01849 double vx, double vy, double va, int state);
01850
01853 int playerc_position2d_set_cmd_pose(playerc_position2d_t *device,
01854 double gx, double gy, double ga, int state);
01855
01857 int playerc_position2d_set_cmd_car(playerc_position2d_t *device,
01858 double vx,double a);
01859
01861 int playerc_position2d_set_odom(playerc_position2d_t *device,
01862 double ox, double oy, double oa);
01863
01865
01866
01867
01878 typedef playerc_position2d_t playerc_position_t;
01879
01881 playerc_position_t *playerc_position_create(playerc_client_t *client,
01882 int index);
01884 void playerc_position_destroy(playerc_position_t *device);
01886 int playerc_position_subscribe(playerc_position_t *device, int access);
01888 int playerc_position_unsubscribe(playerc_position_t *device);
01890 int playerc_position_enable(playerc_position_t *device, int enable);
01893 int playerc_position_get_geom(playerc_position_t *device);
01898 int playerc_position_set_cmd_vel(playerc_position_t *device,
01899 double vx, double vy, double va, int state);
01902 int playerc_position_set_cmd_pose(playerc_position_t *device,
01903 double gx, double gy, double ga, int state);
01905 int playerc_position_set_odom(playerc_position_t *device,
01906 double ox, double oy, double oa);
01910
01925 typedef struct
01926 {
01928 playerc_device_t info;
01929
01933 double pose[3];
01934 double size[2];
01935
01937 double pos_x, pos_y, pos_z;
01938
01940 double pos_roll, pos_pitch, pos_yaw;
01941
01943 double vel_x, vel_y, vel_z;
01944
01946 double vel_roll, vel_pitch, vel_yaw;
01947
01949 int stall;
01950
01951 } playerc_position3d_t;
01952
01953
01955 playerc_position3d_t *playerc_position3d_create(playerc_client_t *client,
01956 int index);
01957
01959 void playerc_position3d_destroy(playerc_position3d_t *device);
01960
01962 int playerc_position3d_subscribe(playerc_position3d_t *device, int access);
01963
01965 int playerc_position3d_unsubscribe(playerc_position3d_t *device);
01966
01968 int playerc_position3d_enable(playerc_position3d_t *device, int enable);
01969
01972 int playerc_position3d_get_geom(playerc_position3d_t *device);
01973
01978 int playerc_position3d_set_velocity(playerc_position3d_t *device,
01979 double vx, double vy, double vz,
01980 double vr, double vp, double vt, int state);
01981
01983 int playerc_position3d_set_speed(playerc_position3d_t *device,
01984 double vx, double vy, double vz, int state);
01985
01988 int playerc_position3d_set_pose(playerc_position3d_t *device,
01989 double gx, double gy, double gz,
01990 double gr, double gp, double gt);
01991
01993 int playerc_position3d_set_cmd_pose(playerc_position3d_t *device,
01994 double gx, double gy, double gz);
01995
01997
01998
01999
02000
02011 typedef struct
02012 {
02014 playerc_device_t info;
02015
02018 int valid;
02019
02021 double charge;
02022
02024 double percent;
02025
02027 double joules;
02028
02031 double watts;
02032
02034 int charging;
02035
02036 } playerc_power_t;
02037
02038
02040 playerc_power_t *playerc_power_create(playerc_client_t *client, int index);
02041
02043 void playerc_power_destroy(playerc_power_t *device);
02044
02046 int playerc_power_subscribe(playerc_power_t *device, int access);
02047
02049 int playerc_power_unsubscribe(playerc_power_t *device);
02050
02051
02053
02054
02055
02056
02057
02068 typedef struct
02069 {
02071 playerc_device_t info;
02072
02076 double pan, tilt;
02077
02079 double zoom;
02080
02081 } playerc_ptz_t;
02082
02083
02085 playerc_ptz_t *playerc_ptz_create(playerc_client_t *client, int index);
02086
02088 void playerc_ptz_destroy(playerc_ptz_t *device);
02089
02091 int playerc_ptz_subscribe(playerc_ptz_t *device, int access);
02092
02094 int playerc_ptz_unsubscribe(playerc_ptz_t *device);
02095
02104 int playerc_ptz_set(playerc_ptz_t *device, double pan, double tilt, double zoom);
02105
02116 int playerc_ptz_set_ws(playerc_ptz_t *device, double pan, double tilt, double zoom,
02117 double panspeed, double tiltspeed);
02118
02119
02121
02122
02123
02134 typedef struct
02135 {
02137 playerc_device_t info;
02138
02140 int pose_count;
02141
02144 player_pose_t poses[PLAYERC_SONAR_MAX_SAMPLES];
02145
02147 int scan_count;
02148
02150 double scan[PLAYERC_SONAR_MAX_SAMPLES];
02151
02152 } playerc_sonar_t;
02153
02154
02156 playerc_sonar_t *playerc_sonar_create(playerc_client_t *client, int index);
02157
02159 void playerc_sonar_destroy(playerc_sonar_t *device);
02160
02162 int playerc_sonar_subscribe(playerc_sonar_t *device, int access);
02163
02165 int playerc_sonar_unsubscribe(playerc_sonar_t *device);
02166
02172 int playerc_sonar_get_geom(playerc_sonar_t *device);
02173
02175
02176
02177
02189 typedef struct
02190 {
02192 char mac[32];
02193
02195 char ip[32];
02196
02198 char essid[32];
02199
02201 int mode;
02202
02204 int encrypt;
02205
02207 double freq;
02208
02210 int qual, level, noise;
02211
02212 } playerc_wifi_link_t;
02213
02214
02216 typedef struct
02217 {
02219 playerc_device_t info;
02220
02222 playerc_wifi_link_t links[PLAYERC_WIFI_MAX_LINKS];
02223 int link_count;
02224
02225 } playerc_wifi_t;
02226
02227
02229 playerc_wifi_t *playerc_wifi_create(playerc_client_t *client, int index);
02230
02232 void playerc_wifi_destroy(playerc_wifi_t *device);
02233
02235 int playerc_wifi_subscribe(playerc_wifi_t *device, int access);
02236
02238 int playerc_wifi_unsubscribe(playerc_wifi_t *device);
02239
02241 playerc_wifi_link_t *playerc_wifi_get_link(playerc_wifi_t *device, int link);
02242
02243
02245 typedef struct
02246 {
02248 playerc_device_t info;
02249
02250 } playerc_simulation_t;
02251
02252
02253
02254 playerc_simulation_t *playerc_simulation_create(playerc_client_t *client, int index);
02255
02256
02257 void playerc_simulation_destroy(playerc_simulation_t *device);
02258
02259
02260 int playerc_simulation_subscribe(playerc_simulation_t *device, int access);
02261
02262
02263 int playerc_simulation_unsubscribe(playerc_simulation_t *device);
02264
02265 int playerc_simulation_set_pose2d(playerc_simulation_t *device, char* name,
02266 double gx, double gy, double ga);
02267
02268 int playerc_simulation_get_pose2d(playerc_simulation_t *device, char* identifier,
02269 double *x, double *y, double *a);
02270
02272
02273
02274
02275
02276
02277
02287 typedef struct
02288 {
02290 playerc_device_t info;
02291
02293 uint8_t count;
02294
02296 uint32_t digin;
02297
02298 } playerc_dio_t;
02299
02300
02302 playerc_dio_t *playerc_dio_create(playerc_client_t *client, int index);
02303
02305 void playerc_dio_destroy(playerc_dio_t *device);
02306
02308 int playerc_dio_subscribe(playerc_dio_t *device, int access);
02309
02311 int playerc_dio_unsubscribe(playerc_dio_t *device);
02312
02314 int playerc_dio_set_output(playerc_dio_t *device, uint8_t output_count, uint32_t digout);
02315
02316
02318
02319
02320
02321
02331 typedef struct
02332 {
02334 playerc_device_t info;
02335 } playerc_speech_t;
02336
02337
02339 playerc_speech_t *playerc_speech_create(playerc_client_t *client, int index);
02340
02342 void playerc_speech_destroy(playerc_speech_t *device);
02343
02345 int playerc_speech_subscribe(playerc_speech_t *device, int access);
02346
02348 int playerc_speech_unsubscribe(playerc_speech_t *device);
02349
02351 int playerc_speech_say (playerc_speech_t *device, const char *);
02352
02353
02355
02356
02357
02366 typedef struct
02367 {
02369 uint32_t type;
02371 uint32_t guid_count;
02373 uint8_t guid[PLAYERC_RFID_MAX_GUID];
02374 } playerc_rfidtag_t;
02375
02377 typedef struct
02378 {
02380 playerc_device_t info;
02381
02383 uint16_t tags_count;
02384
02386 playerc_rfidtag_t tags[PLAYERC_RFID_MAX_TAGS];
02387 } playerc_rfid_t;
02388
02389
02391 playerc_rfid_t *playerc_rfid_create(playerc_client_t *client, int index);
02392
02394 void playerc_rfid_destroy(playerc_rfid_t *device);
02395
02397 int playerc_rfid_subscribe(playerc_rfid_t *device, int access);
02398
02400 int playerc_rfid_unsubscribe(playerc_rfid_t *device);
02401
02403
02404
02405
02406 #ifdef __cplusplus
02407 }
02408 #endif
02409
02410 #endif