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
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046 #ifndef PLAYERC_H
00047 #define PLAYERC_H
00048
00049 #include <stdio.h>
00050
00051
00052 #include "player.h"
00053
00054 #ifndef MIN
00055 #define MIN(a,b) ((a < b) ? a : b)
00056 #endif
00057 #ifndef MAX
00058 #define MAX(a,b) ((a > b) ? a : b)
00059 #endif
00060
00061 #ifdef __cplusplus
00062 extern "C" {
00063 #endif
00064
00065
00066
00067
00068
00069
00071 #define PLAYERC_READ_MODE PLAYER_READ_MODE
00072 #define PLAYERC_WRITE_MODE PLAYER_WRITE_MODE
00073 #define PLAYERC_ALL_MODE PLAYER_ALL_MODE
00074 #define PLAYERC_CLOSE_MODE PLAYER_CLOSE_MODE
00075 #define PLAYERC_ERROR_MODE PLAYER_ERROR_MODE
00076
00078 #define PLAYERC_DATAMODE_PUSH_ALL PLAYER_DATAMODE_PUSH_ALL
00079 #define PLAYERC_DATAMODE_PULL_ALL PLAYER_DATAMODE_PULL_ALL
00080 #define PLAYERC_DATAMODE_PUSH_NEW PLAYER_DATAMODE_PUSH_NEW
00081 #define PLAYERC_DATAMODE_PULL_NEW PLAYER_DATAMODE_PULL_NEW
00082 #define PLAYERC_DATAMODE_PUSH_ASYNC PLAYER_DATAMODE_PUSH_ASYNC
00083
00084
00085
00086
00087
00088
00089 #define PLAYERC_MAX_DEVICES PLAYER_MAX_DEVICES
00090 #define PLAYERC_LASER_MAX_SAMPLES PLAYER_LASER_MAX_SAMPLES
00091 #define PLAYERC_FIDUCIAL_MAX_SAMPLES PLAYER_FIDUCIAL_MAX_SAMPLES
00092 #define PLAYERC_SONAR_MAX_SAMPLES PLAYER_SONAR_MAX_SAMPLES
00093 #define PLAYERC_BUMPER_MAX_SAMPLES PLAYER_BUMPER_MAX_SAMPLES
00094 #define PLAYERC_IR_MAX_SAMPLES PLAYER_IR_MAX_SAMPLES
00095 #define PLAYERC_BLOBFINDER_MAX_BLOBS PLAYER_BLOBFINDER_MAX_BLOBS
00096 #define PLAYERC_WIFI_MAX_LINKS PLAYER_WIFI_MAX_LINKS
00097
00098
00099
00103
00107
00108
00113 const char *playerc_error_str(void);
00114
00116 const char *playerc_lookup_name(int code);
00117
00119 int playerc_lookup_code(const char *name);
00120
00122
00123
00124
00125
00126 struct _playerc_client_t;
00127 struct _playerc_device_t;
00128
00129
00130
00131
00132 struct pollfd;
00133
00134
00135
00143
00144 typedef struct
00145 {
00146 player_msghdr_t header;
00147 int len;
00148 void *data;
00149 } playerc_client_item_t;
00150
00151
00152
00153 typedef struct
00154 {
00155
00156 int client_count;
00157 struct _playerc_client_t *client[128];
00158
00159
00160 struct pollfd* pollfd;
00161
00162
00163 double time;
00164
00165 } playerc_mclient_t;
00166
00167
00168 playerc_mclient_t *playerc_mclient_create(void);
00169
00170
00171 void playerc_mclient_destroy(playerc_mclient_t *mclient);
00172
00173
00174 int playerc_mclient_addclient(playerc_mclient_t *mclient, struct _playerc_client_t *client);
00175
00176
00177
00178 int playerc_mclient_peek(playerc_mclient_t *mclient, int timeout);
00179
00180
00181
00182 int playerc_mclient_read(playerc_mclient_t *mclient, int timeout);
00183
00185
00186
00187
00188
00200 typedef void (*playerc_putdata_fn_t) (void *device, char *header, char *data, size_t len);
00201
00203 typedef void (*playerc_callback_fn_t) (void *data);
00204
00205
00209 typedef struct
00210 {
00212 int port, code, index;
00213
00215 char drivername[PLAYER_MAX_DEVICE_STRING_LEN];
00216
00217 } playerc_device_info_t;
00218
00219
00221 typedef struct _playerc_client_t
00222 {
00225 void *id;
00226
00228 char *host;
00229 int port;
00230
00232 int sock;
00233
00235 int mode;
00236
00239 playerc_device_info_t devinfos[PLAYERC_MAX_DEVICES];
00240 int devinfo_count;
00241
00243 struct _playerc_device_t *device[32];
00244 int device_count;
00245
00247 playerc_client_item_t qitems[128];
00248 int qfirst, qlen, qsize;
00249
00251 char *data;
00252
00254 double datatime;
00255
00256 } playerc_client_t;
00257
00258
00274 playerc_client_t *playerc_client_create(playerc_mclient_t *mclient,
00275 const char *host, int port);
00276
00282 void playerc_client_destroy(playerc_client_t *client);
00283
00292 int playerc_client_connect(playerc_client_t *client);
00293
00302 int playerc_client_disconnect(playerc_client_t *client);
00303
00317 int playerc_client_datamode(playerc_client_t *client, int mode);
00318
00330 int playerc_client_requestdata(playerc_client_t* client);
00331
00343 int playerc_client_datafreq(playerc_client_t *client, int freq);
00344
00347 int playerc_client_adddevice(playerc_client_t *client, struct _playerc_device_t *device);
00348
00349
00352 int playerc_client_deldevice(playerc_client_t *client, struct _playerc_device_t *device);
00353
00356 int playerc_client_addcallback(playerc_client_t *client, struct _playerc_device_t *device,
00357 playerc_callback_fn_t callback, void *data);
00358
00361 int playerc_client_delcallback(playerc_client_t *client, struct _playerc_device_t *device,
00362 playerc_callback_fn_t callback, void *data);
00363
00375 int playerc_client_get_devlist(playerc_client_t *client);
00376
00379 int playerc_client_subscribe(playerc_client_t *client, int code, int index,
00380 int access, char *drivername, size_t len);
00381
00384 int playerc_client_unsubscribe(playerc_client_t *client, int code, int index);
00385
00391 int playerc_client_request(playerc_client_t *client, struct _playerc_device_t *device,
00392 void *req_data, int req_len, void *rep_data, int rep_len);
00393
00404 int playerc_client_peek(playerc_client_t *client, int timeout);
00405
00415 void *playerc_client_read(playerc_client_t *client);
00416
00419 int playerc_client_write(playerc_client_t *client, struct _playerc_device_t *device,
00420 void *cmd, int len);
00421
00422
00424
00425
00426
00427
00439 typedef struct _playerc_device_t
00440 {
00444 void *id;
00445
00447 playerc_client_t *client;
00448
00450 int code, index;
00451
00453 char drivername[PLAYER_MAX_DEVICE_STRING_LEN];
00454
00457 int subscribed;
00458
00460 double datatime;
00461
00465 int fresh;
00466
00468 playerc_putdata_fn_t putdata;
00469
00471 void *user_data;
00472
00474 int callback_count;
00475 playerc_callback_fn_t callback[4];
00476 void *callback_data[4];
00477
00478 } playerc_device_t;
00479
00480
00482 void playerc_device_init(playerc_device_t *device, playerc_client_t *client,
00483 int code, int index, playerc_putdata_fn_t putdata);
00484
00486 void playerc_device_term(playerc_device_t *device);
00487
00489 int playerc_device_subscribe(playerc_device_t *device, int access);
00490
00492 int playerc_device_unsubscribe(playerc_device_t *device);
00493
00495
00496
00497
00498
00502
00503
00504
00505
00516 typedef struct
00517 {
00519 int id;
00520
00523 uint32_t color;
00524
00526 int x, y;
00527
00529 int left, top, right, bottom;
00530
00532 int area;
00533
00535 double range;
00536
00537 } playerc_blobfinder_blob_t;
00538
00539
00541 typedef struct
00542 {
00544 playerc_device_t info;
00545
00547 int width, height;
00548
00550 int blob_count;
00551 playerc_blobfinder_blob_t blobs[PLAYERC_BLOBFINDER_MAX_BLOBS];
00552
00553 } playerc_blobfinder_t;
00554
00555
00557 playerc_blobfinder_t *playerc_blobfinder_create(playerc_client_t *client, int index);
00558
00560 void playerc_blobfinder_destroy(playerc_blobfinder_t *device);
00561
00563 int playerc_blobfinder_subscribe(playerc_blobfinder_t *device, int access);
00564
00566 int playerc_blobfinder_unsubscribe(playerc_blobfinder_t *device);
00567
00569 void playerc_blobfinder_putdata(playerc_blobfinder_t *device, player_msghdr_t *header,
00570 player_blobfinder_data_t *data, size_t len);
00571
00572
00574
00575
00576
00577
00587 typedef struct
00588 {
00590 playerc_device_t info;
00591
00593 int pose_count;
00594
00598 double poses[PLAYERC_BUMPER_MAX_SAMPLES][5];
00599
00601 int bumper_count;
00602
00604 double bumpers[PLAYERC_BUMPER_MAX_SAMPLES];
00605
00606 } playerc_bumper_t;
00607
00608
00610 playerc_bumper_t *playerc_bumper_create(playerc_client_t *client, int index);
00611
00613 void playerc_bumper_destroy(playerc_bumper_t *device);
00614
00616 int playerc_bumper_subscribe(playerc_bumper_t *device, int access);
00617
00619 int playerc_bumper_unsubscribe(playerc_bumper_t *device);
00620
00627 int playerc_bumper_get_geom(playerc_bumper_t *device);
00628
00629
00631
00632
00633
00634
00643 typedef struct
00644 {
00646 playerc_device_t info;
00647
00649 int width, height;
00650
00652 int bpp;
00653
00655 int format;
00656
00660 int fdiv;
00661
00663 int compression;
00664
00666 int image_size;
00667
00672 uint8_t image[PLAYER_CAMERA_IMAGE_SIZE];
00673
00674 } playerc_camera_t;
00675
00676
00678 playerc_camera_t *playerc_camera_create(playerc_client_t *client, int index);
00679
00681 void playerc_camera_destroy(playerc_camera_t *device);
00682
00684 int playerc_camera_subscribe(playerc_camera_t *device, int access);
00685
00687 int playerc_camera_unsubscribe(playerc_camera_t *device);
00688
00690 void playerc_camera_decompress(playerc_camera_t *device);
00691
00692
00694
00695
00696
00710 typedef struct
00711 {
00713 int id;
00714
00716 double range, bearing, orient;
00717
00719 double pos[3];
00720
00722 double rot[3];
00723
00725 double upos[3];
00726
00728 double urot[3];
00729
00730 } playerc_fiducial_item_t;
00731
00732
00734 typedef struct
00735 {
00737 playerc_device_t info;
00738
00743 double pose[3];
00744 double size[2];
00745 double fiducial_size[2];
00746
00748 int fiducial_count;
00749 playerc_fiducial_item_t fiducials[PLAYERC_FIDUCIAL_MAX_SAMPLES];
00750
00751 } playerc_fiducial_t;
00752
00753
00755 playerc_fiducial_t *playerc_fiducial_create(playerc_client_t *client, int index);
00756
00758 void playerc_fiducial_destroy(playerc_fiducial_t *device);
00759
00761 int playerc_fiducial_subscribe(playerc_fiducial_t *device, int access);
00762
00764 int playerc_fiducial_unsubscribe(playerc_fiducial_t *device);
00765
00772 int playerc_fiducial_get_geom(playerc_fiducial_t *device);
00773
00774
00776
00777
00778
00779
00788 typedef struct
00789 {
00791 playerc_device_t info;
00792
00794 double utc_time;
00795
00799 double lat, lon;
00800
00803 double alt;
00804
00806 double utm_e, utm_n;
00807
00809 double hdop;
00810
00812 double vdop;
00813
00815 double err_horz, err_vert;
00816
00818 int quality;
00819
00821 int sat_count;
00822
00823 } playerc_gps_t;
00824
00825
00827 playerc_gps_t *playerc_gps_create(playerc_client_t *client, int index);
00828
00830 void playerc_gps_destroy(playerc_gps_t *device);
00831
00833 int playerc_gps_subscribe(playerc_gps_t *device, int access);
00834
00836 int playerc_gps_unsubscribe(playerc_gps_t *device);
00837
00838
00840
00841
00842
00852 typedef struct
00853 {
00855 playerc_device_t info;
00856
00857
00858 player_ir_data_t ranges;
00859
00860
00861 player_ir_pose_t poses;
00862
00863 } playerc_ir_t;
00864
00865
00867 playerc_ir_t *playerc_ir_create(playerc_client_t *client, int index);
00868
00870 void playerc_ir_destroy(playerc_ir_t *device);
00871
00873 int playerc_ir_subscribe(playerc_ir_t *device, int access);
00874
00876 int playerc_ir_unsubscribe(playerc_ir_t *device);
00877
00884 int playerc_ir_get_geom(playerc_ir_t *device);
00885
00886
00888
00889
00890
00891
00900 typedef struct
00901 {
00903 playerc_device_t info;
00904
00906 double px, py;
00907
00909 uint16_t buttons;
00910
00911 } playerc_joystick_t;
00912
00913
00915 playerc_joystick_t *playerc_joystick_create(playerc_client_t *client, int index);
00916
00918 void playerc_joystick_destroy(playerc_joystick_t *device);
00919
00921 int playerc_joystick_subscribe(playerc_joystick_t *device, int access);
00922
00924 int playerc_joystick_unsubscribe(playerc_joystick_t *device);
00925
00927 void playerc_joystick_putdata(playerc_joystick_t *device, player_msghdr_t *header,
00928 player_joystick_data_t *data, size_t len);
00929
00930
00932
00933
00934
00935
00948 typedef struct
00949 {
00951 playerc_device_t info;
00952
00956 double pose[3];
00957 double size[2];
00958
00960 int scan_count;
00961
00963 double scan_start;
00964
00966 double scan_res;
00967
00969 int range_res;
00970
00972 double ranges[PLAYERC_LASER_MAX_SAMPLES];
00973
00975 double scan[PLAYERC_LASER_MAX_SAMPLES][2];
00976
00978 double point[PLAYERC_LASER_MAX_SAMPLES][2];
00979
00983 int intensity[PLAYERC_LASER_MAX_SAMPLES];
00984
00985 } playerc_laser_t;
00986
00987
00989 playerc_laser_t *playerc_laser_create(playerc_client_t *client, int index);
00990
00992 void playerc_laser_destroy(playerc_laser_t *device);
00993
00995 int playerc_laser_subscribe(playerc_laser_t *device, int access);
00996
00998 int playerc_laser_unsubscribe(playerc_laser_t *device);
00999
01006 void playerc_laser_putdata(playerc_laser_t *device, player_msghdr_t *header,
01007 player_laser_data_t *data, size_t len);
01008
01027 int playerc_laser_set_config(playerc_laser_t *device,
01028 double min_angle, double max_angle,
01029 int resolution, int range_res, int intensity);
01030
01049 int playerc_laser_get_config(playerc_laser_t *device,
01050 double *min_angle, double *max_angle,
01051 int *resolution, int *range_res, int *intensity);
01052
01059 int playerc_laser_get_geom(playerc_laser_t *device);
01060
01062
01063
01064
01080 typedef struct
01081 {
01083 double mean[3];
01084
01086 double cov[3][3];
01087
01089 double weight;
01090
01091 } playerc_localize_hypoth_t;
01092
01093 typedef struct playerc_localize_particle
01094 {
01095 double pose[3];
01096 double weight;
01097 } playerc_localize_particle_t;
01098
01099
01101 typedef struct
01102 {
01104 playerc_device_t info;
01105
01107 int map_size_x, map_size_y;
01108
01110 double map_scale;
01111
01113 int map_tile_x, map_tile_y;
01114
01116 int8_t *map_cells;
01117
01119 int pending_count;
01120
01122 double pending_time;
01123
01125 int hypoth_count;
01126 playerc_localize_hypoth_t hypoths[PLAYER_LOCALIZE_MAX_HYPOTHS];
01127
01128 double mean[3];
01129 double variance;
01130 int num_particles;
01131 playerc_localize_particle_t particles[PLAYER_LOCALIZE_PARTICLES_MAX];
01132
01133 } playerc_localize_t;
01134
01135
01137 playerc_localize_t *playerc_localize_create(playerc_client_t *client, int index);
01138
01140 void playerc_localize_destroy(playerc_localize_t *device);
01141
01143 int playerc_localize_subscribe(playerc_localize_t *device, int access);
01144
01146 int playerc_localize_unsubscribe(playerc_localize_t *device);
01147
01149 int playerc_localize_set_pose(playerc_localize_t *device, double pose[3], double cov[3][3]);
01150
01152 int playerc_localize_get_config(playerc_localize_t *device, player_localize_config_t *config);
01153
01155 int playerc_localize_set_config(playerc_localize_t *device, player_localize_config_t config);
01156
01157
01158
01159 int playerc_localize_get_particles(playerc_localize_t *device);
01160
01162
01163
01164
01165
01174 typedef struct
01175 {
01177 playerc_device_t info;
01178
01181 int type;
01182
01185 int state;
01186 } playerc_log_t;
01187
01188
01190 playerc_log_t *playerc_log_create(playerc_client_t *client, int index);
01191
01193 void playerc_log_destroy(playerc_log_t *device);
01194
01196 int playerc_log_subscribe(playerc_log_t *device, int access);
01197
01199 int playerc_log_unsubscribe(playerc_log_t *device);
01200
01202 int playerc_log_set_write_state(playerc_log_t* device, int state);
01203
01205 int playerc_log_set_read_state(playerc_log_t* device, int state);
01206
01208 int playerc_log_set_read_rewind(playerc_log_t* device);
01209
01215 int playerc_log_get_state(playerc_log_t* device);
01216
01218 int playerc_log_set_filename(playerc_log_t* device, const char* fname);
01219
01220
01225
01234 typedef struct
01235 {
01237 playerc_device_t info;
01238
01240 double resolution;
01241
01243 int width, height;
01244
01246 char* cells;
01247 } playerc_map_t;
01248
01249
01252 #define PLAYERC_MAP_INDEX(dev, i, j) ((dev->width) * (j) + (i))
01253
01255 playerc_map_t *playerc_map_create(playerc_client_t *client, int index);
01256
01258 void playerc_map_destroy(playerc_map_t *device);
01259
01261 int playerc_map_subscribe(playerc_map_t *device, int access);
01262
01264 int playerc_map_unsubscribe(playerc_map_t *device);
01265
01267 int playerc_map_get_map(playerc_map_t* device);
01268
01269
01271
01272
01273
01274
01283 typedef struct
01284 {
01286 playerc_device_t info;
01287
01289 double pt;
01290
01292 double vt;
01293
01295 int stall;
01296
01297 } playerc_motor_t;
01298
01299
01301 playerc_motor_t *playerc_motor_create(playerc_client_t *client, int index);
01302
01304 void playerc_motor_destroy(playerc_motor_t *device);
01305
01307 int playerc_motor_subscribe(playerc_motor_t *device, int access);
01308
01310 int playerc_motor_unsubscribe(playerc_motor_t *device);
01311
01313 int playerc_motor_enable(playerc_motor_t *device, int enable);
01314
01321 int playerc_motor_position_control(playerc_motor_t *device, int type);
01322
01330 int playerc_motor_set_cmd_vel(playerc_motor_t *device,
01331 double vt, int state);
01332
01340 int playerc_motor_set_cmd_pose(playerc_motor_t *device,
01341 double gt, int state);
01342
01344
01345
01346
01355 typedef struct
01356 {
01358 playerc_device_t info;
01359
01361 int path_valid;
01362
01364 int path_done;
01365
01367 double px, py, pa;
01368
01370 double gx, gy, ga;
01371
01373 double wx, wy, wa;
01374
01378 int curr_waypoint;
01379
01381 int waypoint_count;
01382
01385 double waypoints[PLAYER_PLANNER_MAX_WAYPOINTS][3];
01386
01387 } playerc_planner_t;
01388
01390 playerc_planner_t *playerc_planner_create(playerc_client_t *client, int index);
01391
01393 void playerc_planner_destroy(playerc_planner_t *device);
01394
01396 int playerc_planner_subscribe(playerc_planner_t *device, int access);
01397
01399 int playerc_planner_unsubscribe(playerc_planner_t *device);
01400
01402 int playerc_planner_set_cmd_pose(playerc_planner_t *device,
01403 double gx, double gy, double ga);
01404
01411 int playerc_planner_get_waypoints(playerc_planner_t *device);
01412
01418 int playerc_planner_enable(playerc_planner_t *device, int state);
01419
01421
01422
01423
01424
01438 typedef struct
01439 {
01441 playerc_device_t info;
01442
01446 double pose[3];
01447 double size[2];
01448
01450 double px, py, pa;
01451
01453 double vx, vy, va;
01454
01456 int stall;
01457 } playerc_position_t;
01458
01459
01461 playerc_position_t *playerc_position_create(playerc_client_t *client, int index);
01462
01464 void playerc_position_destroy(playerc_position_t *device);
01465
01467 int playerc_position_subscribe(playerc_position_t *device, int access);
01468
01470 int playerc_position_unsubscribe(playerc_position_t *device);
01471
01473 void playerc_position_putdata(playerc_position_t *device, player_msghdr_t *header,
01474 player_position_data_t *data, size_t len);
01475
01476
01478 int playerc_position_enable(playerc_position_t *device, int enable);
01479
01486 int playerc_position_get_geom(playerc_position_t *device);
01487
01499 int playerc_position_set_cmd_vel(playerc_position_t *device,
01500 double vx, double vy, double va, int state);
01501
01509 int playerc_position_set_cmd_pose(playerc_position_t *device,
01510 double gx, double gy, double ga, int state);
01511
01512
01514
01515
01516
01517
01534 typedef struct
01535 {
01537 playerc_device_t info;
01538
01542 double pose[3];
01543 double size[2];
01544
01546 double px, py, pa;
01547
01549 double vx, vy, va;
01550
01552 int stall;
01553
01554 } playerc_position2d_t;
01555
01556
01558 playerc_position2d_t *playerc_position2d_create(playerc_client_t *client, int index);
01559
01561 void playerc_position2d_destroy(playerc_position2d_t *device);
01562
01564 int playerc_position2d_subscribe(playerc_position2d_t *device, int access);
01565
01567 int playerc_position2d_unsubscribe(playerc_position2d_t *device);
01568
01570 int playerc_position2d_enable(playerc_position2d_t *device, int enable);
01571
01574 int playerc_position2d_get_geom(playerc_position2d_t *device);
01575
01580 int playerc_position2d_set_cmd_vel(playerc_position2d_t *device,
01581 double vx, double vy, double va, int state);
01582
01585 int playerc_position2d_set_cmd_pose(playerc_position2d_t *device,
01586 double gx, double gy, double ga, int state);
01587
01589
01590
01591
01592
01606 typedef struct
01607 {
01609 playerc_device_t info;
01610
01614 double pose[3];
01615 double size[2];
01616
01618 double pos_x, pos_y, pos_z;
01619
01621 double pos_roll, pos_pitch, pos_yaw;
01622
01624 double vel_x, vel_y, vel_z;
01625
01627 double vel_roll, vel_pitch, vel_yaw;
01628
01630 int stall;
01631
01632 } playerc_position3d_t;
01633
01634
01636 playerc_position3d_t *playerc_position3d_create(playerc_client_t *client,
01637 int index);
01638
01640 void playerc_position3d_destroy(playerc_position3d_t *device);
01641
01643 int playerc_position3d_subscribe(playerc_position3d_t *device, int access);
01644
01646 int playerc_position3d_unsubscribe(playerc_position3d_t *device);
01647
01649 void playerc_position3d_putdata(playerc_position3d_t *device, player_msghdr_t *header,
01650 player_position3d_data_t *data, size_t len);
01651
01653 int playerc_position3d_enable(playerc_position3d_t *device, int enable);
01654
01657 int playerc_position3d_get_geom(playerc_position3d_t *device);
01658
01663 int playerc_position3d_set_velocity(playerc_position3d_t *device,
01664 double vx, double vy, double vz,
01665 double vr, double vp, double vt, int state);
01666
01668 int playerc_position3d_set_speed(playerc_position3d_t *device,
01669 double vx, double vy, double vz, int state);
01670
01673 int playerc_position3d_set_pose(playerc_position3d_t *device,
01674 double gx, double gy, double gz,
01675 double gr, double gp, double gt);
01676
01678 int playerc_position3d_set_cmd_pose(playerc_position3d_t *device,
01679 double gx, double gy, double gz);
01680
01682
01683
01684
01694 typedef struct
01695 {
01697 playerc_device_t info;
01698
01700 double charge;
01701
01702 } playerc_power_t;
01703
01704
01706 playerc_power_t *playerc_power_create(playerc_client_t *client, int index);
01707
01709 void playerc_power_destroy(playerc_power_t *device);
01710
01712 int playerc_power_subscribe(playerc_power_t *device, int access);
01713
01715 int playerc_power_unsubscribe(playerc_power_t *device);
01716
01717
01719
01720
01721
01722
01732 typedef struct
01733 {
01735 playerc_device_t info;
01736
01740 double pan, tilt;
01741
01743 double zoom;
01744
01745 } playerc_ptz_t;
01746
01747
01749 playerc_ptz_t *playerc_ptz_create(playerc_client_t *client, int index);
01750
01752 void playerc_ptz_destroy(playerc_ptz_t *device);
01753
01755 int playerc_ptz_subscribe(playerc_ptz_t *device, int access);
01756
01758 int playerc_ptz_unsubscribe(playerc_ptz_t *device);
01759
01768 int playerc_ptz_set(playerc_ptz_t *device, double pan, double tilt, double zoom);
01769
01780 int playerc_ptz_set_ws(playerc_ptz_t *device, double pan, double tilt, double zoom,
01781 double panspeed, double tiltspeed);
01782
01783
01785
01786
01787
01788
01798 typedef struct
01799 {
01801 playerc_device_t info;
01802
01804 int pose_count;
01805
01808 double poses[PLAYERC_SONAR_MAX_SAMPLES][3];
01809
01811 int scan_count;
01812
01814 double scan[PLAYERC_SONAR_MAX_SAMPLES];
01815
01816 } playerc_sonar_t;
01817
01818
01820 playerc_sonar_t *playerc_sonar_create(playerc_client_t *client, int index);
01821
01823 void playerc_sonar_destroy(playerc_sonar_t *device);
01824
01826 int playerc_sonar_subscribe(playerc_sonar_t *device, int access);
01827
01829 int playerc_sonar_unsubscribe(playerc_sonar_t *device);
01830
01836 int playerc_sonar_get_geom(playerc_sonar_t *device);
01837
01839
01840
01841
01842
01852 typedef struct
01853 {
01855 playerc_device_t info;
01856
01858 double pos[3];
01859
01861 double rot[3];
01862
01863 } playerc_truth_t;
01864
01865
01867 playerc_truth_t *playerc_truth_create(playerc_client_t *client, int index);
01868
01870 void playerc_truth_destroy(playerc_truth_t *device);
01871
01873 int playerc_truth_subscribe(playerc_truth_t *device, int access);
01874
01876 int playerc_truth_unsubscribe(playerc_truth_t *device);
01877
01883 int playerc_truth_get_pose(playerc_truth_t *device,
01884 double *px, double *py, double *pz,
01885 double *rx, double *ry, double *rz);
01886
01892 int playerc_truth_set_pose(playerc_truth_t *device,
01893 double px, double py, double pz,
01894 double rx, double ry, double rz);
01895
01896
01898
01899
01900
01901
01912 typedef struct
01913 {
01915 char mac[32];
01916
01918 char ip[32];
01919
01921 char essid[32];
01922
01924 int mode;
01925
01927 int encrypt;
01928
01930 double freq;
01931
01933 int qual, level, noise;
01934
01935 } playerc_wifi_link_t;
01936
01937
01939 typedef struct
01940 {
01942 playerc_device_t info;
01943
01945 playerc_wifi_link_t links[PLAYERC_WIFI_MAX_LINKS];
01946 int link_count;
01947
01948 } playerc_wifi_t;
01949
01950
01952 playerc_wifi_t *playerc_wifi_create(playerc_client_t *client, int index);
01953
01955 void playerc_wifi_destroy(playerc_wifi_t *device);
01956
01958 int playerc_wifi_subscribe(playerc_wifi_t *device, int access);
01959
01961 int playerc_wifi_unsubscribe(playerc_wifi_t *device);
01962
01964 playerc_wifi_link_t *playerc_wifi_get_link(playerc_wifi_t *device, int link);
01965
01967 typedef struct
01968 {
01970 playerc_device_t info;
01971
01972 } playerc_simulation_t;
01973
01974
01975
01976 playerc_simulation_t *playerc_simulation_create(playerc_client_t *client, int index);
01977
01978
01979 void playerc_simulation_destroy(playerc_simulation_t *device);
01980
01981
01982 int playerc_simulation_subscribe(playerc_simulation_t *device, int access);
01983
01984
01985 int playerc_simulation_unsubscribe(playerc_simulation_t *device);
01986
01987
01988 void playerc_simulation_putdata(playerc_simulation_t *device, player_msghdr_t *header,
01989 player_simulation_data_t *data, size_t len);
01990
01991 int playerc_simulation_set_pose2d(playerc_simulation_t *device, char* name,
01992 double gx, double gy, double ga);
01993
01994 int playerc_simulation_get_pose2d(playerc_simulation_t *device, char* identifier,
01995 double *x, double *y, double *a);
01996
01998
01999
02000
02009 typedef struct
02010 {
02012 playerc_device_t info;
02013
02014 unsigned char state;
02015 unsigned char beams;
02016 int outer_break_beam;
02017 int inner_break_beam;
02018 int paddles_open;
02019 int paddles_closed;
02020 int paddles_moving;
02021 int gripper_error;
02022 int lift_up;
02023 int lift_down;
02024 int lift_moving;
02025 int lift_error;
02026
02027 } playerc_gripper_t;
02028
02029
02031 playerc_gripper_t *playerc_gripper_create(playerc_client_t *client, int index);
02032
02034 void playerc_gripper_destroy(playerc_gripper_t *device);
02035
02037 int playerc_gripper_subscribe(playerc_gripper_t *device, int access);
02038
02040 int playerc_gripper_unsubscribe(playerc_gripper_t *device);
02041
02043 int playerc_gripper_set_cmd(playerc_gripper_t *device, uint8_t cmd, uint8_t arg);
02044
02045
02054 typedef struct
02055 {
02057 playerc_device_t info;
02058
02060 uint8_t count;
02061
02063 uint32_t digin;
02064
02065 } playerc_dio_t;
02066
02067
02069 playerc_dio_t *playerc_dio_create(playerc_client_t *client, int index);
02070
02072 void playerc_dio_destroy(playerc_dio_t *device);
02073
02075 int playerc_dio_subscribe(playerc_dio_t *device, int access);
02076
02078 int playerc_dio_unsubscribe(playerc_dio_t *device);
02079
02081 int playerc_dio_set_output(playerc_dio_t *device, uint8_t output_count, uint32_t digout);
02082
02083
02085
02086
02087
02088
02097 typedef struct
02098 {
02100 playerc_device_t info;
02101 } playerc_speech_t;
02102
02103
02105 playerc_speech_t *playerc_speech_create(playerc_client_t *client, int index);
02106
02108 void playerc_speech_destroy(playerc_speech_t *device);
02109
02111 int playerc_speech_subscribe(playerc_speech_t *device, int access);
02112
02114 int playerc_speech_unsubscribe(playerc_speech_t *device);
02115
02117 int playerc_speech_say (playerc_speech_t *device, char *);
02118
02119
02121
02122
02123
02124
02126
02127
02130 #ifdef __cplusplus
02131 }
02132 #endif
02133
02134 #endif