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 #ifndef GAZEBO_H
00029 #define GAZEBO_H
00030
00031 #include <sys/types.h>
00032 #include <stdlib.h>
00033 #include <stdint.h>
00034
00035
00036 #ifdef __cplusplus
00037 extern "C" {
00038 #endif
00039
00046
00047
00048
00049
00052
00054 #define LIBGAZEBO_VERSION 0x050
00055
00057
00058
00061
00064
00065
00071 void gz_error_init(int print, int level);
00072
00077 const char *gz_error_str(void);
00078
00080
00081
00082
00083
00084
00087
00097
00098 typedef struct gz_server
00099 {
00101 int server_id;
00102
00104 char *filename;
00105
00107 int sem_key, sem_cid;
00108
00109 } gz_server_t;
00110
00111
00113 extern gz_server_t *gz_server_alloc();
00114
00116 extern void gz_server_free(gz_server_t *self);
00117
00119 extern int gz_server_init(gz_server_t *self, int server_id, int force);
00120
00122 extern int gz_server_fini(gz_server_t *self);
00123
00125 extern int gz_server_post(gz_server_t *self);
00126
00128
00129
00130
00131
00132
00135
00143
00144 #define GZ_SEM_KEY 0x135135FA
00145
00151 #define GZ_CLIENT_ID_USER_FIRST 0x00
00152 #define GZ_CLIENT_ID_USER_LAST 0x07
00153 #define GZ_CLIENT_ID_WXGAZEBO 0x08
00154 #define GZ_CLIENT_ID_PLAYER 0x09
00155
00156
00158 typedef struct gz_client
00159 {
00161 int server_id;
00162
00164 int client_id;
00165
00167 char *filename;
00168
00170 int sem_key, sem_cid;
00171
00172 } gz_client_t;
00173
00174
00176 extern gz_client_t *gz_client_alloc();
00177
00179 extern void gz_client_free(gz_client_t *self);
00180
00184 extern int gz_client_query(gz_client_t *self, int server_id);
00185
00187 extern int gz_client_connect(gz_client_t *self, int server_id);
00188
00193 extern int gz_client_connect_wait(gz_client_t *self, int server_id, int client_id);
00194
00196 extern int gz_client_disconnect(gz_client_t *self);
00197
00200 extern int gz_client_wait(gz_client_t *self);
00201
00203
00204
00205
00206
00209
00216
00217 #define GAZEBO_MAX_MODEL_TYPE 128
00218
00220 typedef struct gz_data
00221 {
00223 int version;
00224
00226 size_t size;
00227
00229 char model_type[GAZEBO_MAX_MODEL_TYPE];
00230
00232 int model_id;
00233
00235 int parent_model_id;
00236
00237 } gz_data_t;
00238
00240
00241
00242
00243
00244
00247
00254 typedef struct gz_iface
00255 {
00256
00257 gz_server_t *server;
00258
00259
00260 gz_client_t *client;
00261
00262
00263 int mmap_fd;
00264
00265
00266 void *mmap;
00267
00268
00269 char *filename;
00270
00271 } gz_iface_t;
00272
00273
00274
00275 extern gz_iface_t *gz_iface_alloc();
00276
00277
00278 extern void gz_iface_free(gz_iface_t *self);
00279
00280
00281 extern int gz_iface_create(gz_iface_t *self, gz_server_t *server,
00282 const char *type, const char *id, size_t size);
00283
00284
00285 extern int gz_iface_destroy(gz_iface_t *self);
00286
00287
00288 extern int gz_iface_open(gz_iface_t *self, gz_client_t *client,
00289 const char *type, const char *id, size_t size);
00290
00291
00292 extern int gz_iface_close(gz_iface_t *self);
00293
00294
00295
00296 extern int gz_iface_lock(gz_iface_t *self, int blocking);
00297
00298
00299 extern void gz_iface_unlock(gz_iface_t *self);
00300
00301
00302 extern int gz_iface_post(gz_iface_t *self);
00303
00304
00306
00307
00308
00309
00312
00320
00321 typedef struct gz_sim_data
00322 {
00324 gz_data_t head;
00325
00327 double sim_time;
00328
00331 double pause_time;
00332
00333
00334 double real_time;
00335
00337 int pause;
00338
00340 int reset;
00341
00343 int save;
00344
00345 } gz_sim_data_t;
00346
00347
00349 typedef struct gz_sim
00350 {
00352 gz_iface_t *iface;
00353
00355 gz_sim_data_t *data;
00356
00357 } gz_sim_t;
00358
00359
00361 extern gz_sim_t *gz_sim_alloc();
00362
00364 extern void gz_sim_free(gz_sim_t *self);
00365
00370 extern int gz_sim_create(gz_sim_t *self, gz_server_t *server, const char *id);
00371
00373 extern int gz_sim_destroy(gz_sim_t *self);
00374
00379 extern int gz_sim_open(gz_sim_t *self, gz_client_t *client, const char *id);
00380
00382 extern int gz_sim_close(gz_sim_t *self);
00383
00386 extern int gz_sim_lock(gz_sim_t *self, int blocking);
00387
00389 extern void gz_sim_unlock(gz_sim_t *self);
00390
00392
00393
00394
00395
00398
00409
00410
00411 #define GAZEBO_CAMERA_MAX_IMAGE_SIZE 320 * 240 * 3
00412
00414 typedef struct gz_camera_data
00415 {
00417 gz_data_t head;
00418
00420 double time;
00421
00423 unsigned int width, height;
00424
00426 unsigned int image_size;
00427 unsigned char image[GAZEBO_CAMERA_MAX_IMAGE_SIZE];
00428
00429 } gz_camera_data_t;
00430
00431
00433 typedef struct gz_camera
00434 {
00436 gz_iface_t *iface;
00437
00439 gz_camera_data_t *data;
00440
00441 } gz_camera_t;
00442
00443
00445 extern gz_camera_t *gz_camera_alloc();
00446
00448 extern void gz_camera_free(gz_camera_t *self);
00449
00451 extern int gz_camera_create(gz_camera_t *self, gz_server_t *server, const char *id,
00452 const char *model_type, int model_id, int parent_model_id);
00453
00455 extern int gz_camera_destroy(gz_camera_t *self);
00456
00458 extern int gz_camera_open(gz_camera_t *self, gz_client_t *client, const char *id);
00459
00461 extern int gz_camera_close(gz_camera_t *self);
00462
00465 extern int gz_camera_lock(gz_camera_t *self, int blocking);
00466
00468 extern void gz_camera_unlock(gz_camera_t *self);
00469
00471 extern int gz_camera_post(gz_camera_t *self);
00472
00474
00475
00476
00477
00480
00488
00489 typedef struct gz_factory_data
00490 {
00492 gz_data_t head;
00493
00495 double time;
00496
00498 uint8_t string[4096];
00499
00500 } gz_factory_data_t;
00501
00502
00504 typedef struct gz_factory
00505 {
00507 gz_iface_t *iface;
00508
00510 gz_factory_data_t *data;
00511
00512 } gz_factory_t;
00513
00514
00516 extern gz_factory_t *gz_factory_alloc();
00517
00519 extern void gz_factory_free(gz_factory_t *self);
00520
00522 extern int gz_factory_create(gz_factory_t *self, gz_server_t *server, const char *id,
00523 const char *model_type, int model_id, int parent_model_id);
00524
00526 extern int gz_factory_destroy(gz_factory_t *self);
00527
00529 extern int gz_factory_open(gz_factory_t *self, gz_client_t *client, const char *id);
00530
00532 extern int gz_factory_close(gz_factory_t *self);
00533
00536 extern int gz_factory_lock(gz_factory_t *self, int blocking);
00537
00539 extern void gz_factory_unlock(gz_factory_t *self);
00540
00542
00543
00544
00545
00548
00558 #define GZ_FIDUCIAL_MAX_FIDS 401
00559
00561 typedef struct gz_fiducial_fid
00562 {
00564 int id;
00565
00567 double pos[3];
00568
00570 double rot[3];
00571
00572 } gz_fiducial_fid_t;
00573
00574
00576 typedef struct gz_fiducial_data
00577 {
00579 gz_data_t head;
00580
00582 double time;
00583
00585 int fid_count;
00586 gz_fiducial_fid_t fids[GZ_FIDUCIAL_MAX_FIDS];
00587
00588 } gz_fiducial_data_t;
00589
00590
00592 typedef struct gz_fiducial
00593 {
00595 gz_iface_t *iface;
00596
00598 gz_fiducial_data_t *data;
00599
00600 } gz_fiducial_t;
00601
00602
00604 extern gz_fiducial_t *gz_fiducial_alloc();
00605
00607 extern void gz_fiducial_free(gz_fiducial_t *self);
00608
00610 extern int gz_fiducial_create(gz_fiducial_t *self, gz_server_t *server, const char *id,
00611 const char *model_type, int model_id, int parent_model_id);
00612
00614 extern int gz_fiducial_destroy(gz_fiducial_t *self);
00615
00617 extern int gz_fiducial_open(gz_fiducial_t *self, gz_client_t *client, const char *id);
00618
00620 extern int gz_fiducial_close(gz_fiducial_t *self);
00621
00624 extern int gz_fiducial_lock(gz_fiducial_t *self, int blocking);
00625
00627 extern void gz_fiducial_unlock(gz_fiducial_t *self);
00628
00630 extern int gz_fiducial_post(gz_fiducial_t *self);
00631
00633
00634
00635
00636
00639
00648
00649 #define GAZEBO_GUICAM_MAX_IMAGE_SIZE 1024 * 768 * 3
00650
00652 typedef struct gz_guicam_data
00653 {
00655 gz_data_t head;
00656
00658 double sim_time;
00659
00662 double pause_time;
00663
00665 double pos[3];
00666
00668 double rot[3];
00669
00671 int cmd_spot_mode;
00672
00674 int cmd_spot_state;
00675
00677 double cmd_spot_a[2], cmd_spot_b[2];
00678
00681 int roll_lock;
00682
00684 int display_bbox;
00685
00687 int display_axes;
00688
00690 int display_com;
00691
00693 int display_skins;
00694
00696 int display_rays;
00697
00699 int display_frustrums;
00700
00702 int display_materials;
00703
00705 int display_textures;
00706
00708 int polygon_fill;
00709
00711 int shade_smooth;
00712
00714 int save_frames;
00715
00717 unsigned int width, height;
00718
00720 unsigned char image[GAZEBO_GUICAM_MAX_IMAGE_SIZE];
00721 unsigned int image_size;
00722
00723 } gz_guicam_data_t;
00724
00725
00727 typedef struct gz_guicam
00728 {
00730 gz_iface_t *iface;
00731
00733 gz_guicam_data_t *data;
00734
00735 } gz_guicam_t;
00736
00737
00739 extern gz_guicam_t *gz_guicam_alloc();
00740
00742 extern void gz_guicam_free(gz_guicam_t *self);
00743
00745 extern int gz_guicam_create(gz_guicam_t *self, gz_server_t *server, const char *id,
00746 const char *model_type, int model_id, int parent_model_id);
00747
00749 extern int gz_guicam_destroy(gz_guicam_t *self);
00750
00752 extern int gz_guicam_open(gz_guicam_t *self, gz_client_t *client, const char *id);
00753
00755 extern int gz_guicam_close(gz_guicam_t *self);
00756
00759 extern int gz_guicam_lock(gz_guicam_t *self, int blocking);
00760
00762 extern void gz_guicam_unlock(gz_guicam_t *self);
00763
00765 extern int gz_guicam_post(gz_guicam_t *self);
00766
00768
00769
00770
00771
00774
00783
00784 typedef struct gz_gps_data
00785 {
00787 gz_data_t head;
00788
00790 double time;
00791
00793 double utc_time;
00794
00796 double latitude;
00797
00799 double longitude;
00800
00802 double altitude;
00803
00805 double utm_e, utm_n;
00806
00808 int satellites;
00809
00811 int quality;
00812
00814 double hdop;
00815
00817 double vdop;
00818
00820 double err_horz, err_vert;
00821
00822 } gz_gps_data_t;
00823
00824
00826 typedef struct gz_gps
00827 {
00829 gz_iface_t *iface;
00830
00832 gz_gps_data_t *data;
00833
00834 } gz_gps_t;
00835
00836
00838 extern gz_gps_t *gz_gps_alloc();
00839
00841 extern void gz_gps_free(gz_gps_t *self);
00842
00844 extern int gz_gps_create(gz_gps_t *self, gz_server_t *server, const char *id,
00845 const char *model_type, int model_id, int parent_model_id);
00846
00848 extern int gz_gps_destroy(gz_gps_t *self);
00849
00851 extern int gz_gps_open(gz_gps_t *self, gz_client_t *client, const char *id);
00852
00854 extern int gz_gps_close(gz_gps_t *self);
00855
00858 extern int gz_gps_lock(gz_gps_t *self, int blocking);
00859
00861 extern void gz_gps_unlock(gz_gps_t *self);
00862
00864 extern int gz_gps_post(gz_gps_t *self);
00865
00867
00868
00869
00870
00871
00874
00882
00883 typedef struct gz_gripper_data
00884 {
00886 gz_data_t head;
00887
00889 double time;
00890
00891 int cmd;
00892 int lift_limit_reach;
00893 int grip_limit_reach;
00894 int outer_beam_obstruct;
00895 int inner_beam_obstruct;
00896 int left_paddle_open;
00897 int right_paddle_open;
00898 int paddles_opened;
00899 int paddles_closed;
00900 int paddles_moving;
00901 int paddles_error;
00902 int lift_up;
00903 int lift_down;
00904 int lift_moving;
00905 int lift_error;
00906
00907 } gz_gripper_data_t;
00908
00909
00911 typedef struct gz_gripper
00912 {
00914 gz_iface_t *iface;
00915
00917 gz_gripper_data_t *data;
00918
00919 } gz_gripper_t;
00920
00921
00923 extern gz_gripper_t *gz_gripper_alloc();
00924
00926 extern void gz_gripper_free(gz_gripper_t *self);
00927
00929 extern int gz_gripper_create(gz_gripper_t *self, gz_server_t *server, const char *id,
00930 const char *model_type, int model_id, int parent_model_id);
00931
00933 extern int gz_gripper_destroy(gz_gripper_t *self);
00934
00936 extern int gz_gripper_open(gz_gripper_t *self, gz_client_t *client, const char *id);
00937
00939 extern int gz_gripper_close(gz_gripper_t *self);
00940
00943 extern int gz_gripper_lock(gz_gripper_t *self, int blocking);
00944
00946 extern void gz_gripper_unlock(gz_gripper_t *self);
00947
00949
00950
00951
00952
00955
00964 #define GZ_LASER_MAX_RANGES 401
00965
00967 typedef struct gz_laser_data
00968 {
00970 gz_data_t head;
00971
00973 double time;
00974
00976 double min_angle, max_angle;
00977
00979 double res_angle;
00980
00982 double max_range;
00983
00985 int range_count;
00986
00988 double ranges[GZ_LASER_MAX_RANGES];
00989
00991 int intensity[GZ_LASER_MAX_RANGES];
00992
00993
00994 int cmd_new_angle;
00995 int cmd_new_length;
00996
00997
00998 double cmd_max_range;
00999 double cmd_min_angle, cmd_max_angle;
01000 int cmd_range_count;
01001
01002 } gz_laser_data_t;
01003
01004
01006 typedef struct gz_laser
01007 {
01009 gz_iface_t *iface;
01010
01012 gz_laser_data_t *data;
01013
01014 } gz_laser_t;
01015
01016
01018 extern gz_laser_t *gz_laser_alloc();
01019
01021 extern void gz_laser_free(gz_laser_t *self);
01022
01024 extern int gz_laser_create(gz_laser_t *self, gz_server_t *server, const char *id,
01025 const char *model_type, int model_id, int parent_model_id);
01026
01028 extern int gz_laser_destroy(gz_laser_t *self);
01029
01031 extern int gz_laser_open(gz_laser_t *self, gz_client_t *client, const char *id);
01032
01034 extern int gz_laser_close(gz_laser_t *self);
01035
01038 extern int gz_laser_lock(gz_laser_t *self, int blocking);
01039
01041 extern void gz_laser_unlock(gz_laser_t *self);
01042
01044 extern int gz_laser_post(gz_laser_t *self);
01045
01047
01048
01049
01050
01053
01062
01063 typedef struct gz_position_data
01064 {
01066 gz_data_t head;
01067
01069 double time;
01070
01072 double pos[3];
01073 double rot[3];
01074
01076 double vel_pos[3];
01077 double vel_rot[3];
01078
01080 int stall;
01081
01083 int cmd_enable_motors;
01084
01086 double cmd_vel_pos[3];
01087 double cmd_vel_rot[3];
01088
01089 } gz_position_data_t;
01090
01091
01093 typedef struct gz_position
01094 {
01096 gz_iface_t *iface;
01097
01099 gz_position_data_t *data;
01100
01101 } gz_position_t;
01102
01103
01105 extern gz_position_t *gz_position_alloc();
01106
01108 extern void gz_position_free(gz_position_t *self);
01109
01111 extern int gz_position_create(gz_position_t *self, gz_server_t *server, const char *id,
01112 const char *model_type, int model_id, int parent_model_id);
01113
01115 extern int gz_position_destroy(gz_position_t *self);
01116
01118 extern int gz_position_open(gz_position_t *self, gz_client_t *client, const char *id);
01119
01121 extern int gz_position_close(gz_position_t *self);
01122
01125 extern int gz_position_lock(gz_position_t *self, int blocking);
01126
01128 extern void gz_position_unlock(gz_position_t *self);
01129
01131 extern int gz_position_post(gz_position_t *self);
01132
01134
01135
01136
01137
01140
01148
01149 typedef struct gz_power_data
01150 {
01152 gz_data_t head;
01153
01155 double time;
01156
01158 double levels[10];
01159
01160 } gz_power_data_t;
01161
01162
01164 typedef struct gz_power
01165 {
01167 gz_iface_t *iface;
01168
01170 gz_power_data_t *data;
01171
01172 } gz_power_t;
01173
01174
01176 extern gz_power_t *gz_power_alloc();
01177
01179 extern void gz_power_free(gz_power_t *self);
01180
01182 extern int gz_power_create(gz_power_t *self, gz_server_t *server, const char *id,
01183 const char *model_type, int model_id, int parent_model_id);
01184
01186 extern int gz_power_destroy(gz_power_t *self);
01187
01189 extern int gz_power_open(gz_power_t *self, gz_client_t *client, const char *id);
01190
01192 extern int gz_power_close(gz_power_t *self);
01193
01196 extern int gz_power_lock(gz_power_t *self, int blocking);
01197
01199 extern void gz_power_unlock(gz_power_t *self);
01200
01202 extern int gz_power_post(gz_power_t *self);
01203
01205
01206
01207
01208
01211
01219
01220 typedef struct gz_ptz_data
01221 {
01223 gz_data_t head;
01224
01226 double time;
01227
01229 double pan, tilt;
01230
01232 double zoom;
01233
01235 double cmd_pan, cmd_tilt;
01236
01238 double cmd_zoom;
01239
01240 } gz_ptz_data_t;
01241
01242
01244 typedef struct gz_ptz
01245 {
01247 gz_data_t head;
01248
01250 gz_iface_t *iface;
01251
01253 gz_ptz_data_t *data;
01254
01255 } gz_ptz_t;
01256
01257
01259 extern gz_ptz_t *gz_ptz_alloc();
01260
01262 extern void gz_ptz_free(gz_ptz_t *self);
01263
01265 extern int gz_ptz_create(gz_ptz_t *self, gz_server_t *server, const char *id,
01266 const char *model_type, int model_id, int parent_model_id);
01267
01269 extern int gz_ptz_destroy(gz_ptz_t *self);
01270
01272 extern int gz_ptz_open(gz_ptz_t *self, gz_client_t *client, const char *id);
01273
01275 extern int gz_ptz_close(gz_ptz_t *self);
01276
01279 extern int gz_ptz_lock(gz_ptz_t *self, int blocking);
01280
01282 extern void gz_ptz_unlock(gz_ptz_t *self);
01283
01285 extern int gz_ptz_post(gz_ptz_t *self);
01286
01287
01289
01290
01291
01292
01295
01303 #define GZ_SONAR_MAX_RANGES 48
01304
01306 typedef struct gz_sonar_data
01307 {
01309 gz_data_t head;
01310
01312 double time;
01313
01315 double max_range;
01316
01318 int sonar_count;
01319
01321 double sonar_pos[GZ_SONAR_MAX_RANGES][3];
01322
01324 double sonar_rot[GZ_SONAR_MAX_RANGES][3];
01325
01327 double sonar_ranges[GZ_SONAR_MAX_RANGES];
01328
01330 int cmd_enable_sonar;
01331
01332 } gz_sonar_data_t;
01333
01334
01336 typedef struct gz_sonar
01337 {
01339 gz_iface_t *iface;
01340
01342 gz_sonar_data_t *data;
01343
01344 } gz_sonar_t;
01345
01346
01348 extern gz_sonar_t *gz_sonar_alloc();
01349
01351 extern void gz_sonar_free(gz_sonar_t *self);
01352
01354 extern int gz_sonar_create(gz_sonar_t *self, gz_server_t *server, const char *id,
01355 const char *model_type, int model_id, int parent_model_id);
01356
01358 extern int gz_sonar_destroy(gz_sonar_t *self);
01359
01361 extern int gz_sonar_open(gz_sonar_t *self, gz_client_t *client, const char *id);
01362
01364 extern int gz_sonar_close(gz_sonar_t *self);
01365
01368 extern int gz_sonar_lock(gz_sonar_t *self, int blocking);
01369
01371 extern void gz_sonar_unlock(gz_sonar_t *self);
01372
01374
01375
01376
01377
01380
01389
01390 #define GAZEBO_STEREO_MAX_RGB_SIZE 640 * 480 * 3
01391 #define GAZEBO_STEREO_MAX_DISPARITY_SIZE 640 * 480
01392
01394 typedef struct gz_stereo_data
01395 {
01397 gz_data_t head;
01398
01400 double time;
01401
01403 unsigned int width, height;
01404
01406 unsigned int left_image_size;
01407 unsigned char left_image[GAZEBO_STEREO_MAX_RGB_SIZE];
01408
01410 unsigned int right_image_size;
01411 unsigned char right_image[GAZEBO_STEREO_MAX_RGB_SIZE];
01412
01414 unsigned int left_disparity_size;
01415 float left_disparity[GAZEBO_STEREO_MAX_DISPARITY_SIZE];
01416
01418 unsigned int right_disparity_size;
01419 float right_disparity[GAZEBO_STEREO_MAX_DISPARITY_SIZE];
01420
01421 } gz_stereo_data_t;
01422
01423
01425 typedef struct gz_stereo
01426 {
01428 gz_iface_t *iface;
01429
01431 gz_stereo_data_t *data;
01432
01433 } gz_stereo_t;
01434
01435
01437 extern gz_stereo_t *gz_stereo_alloc();
01438
01440 extern void gz_stereo_free(gz_stereo_t *self);
01441
01443 extern int gz_stereo_create(gz_stereo_t *self, gz_server_t *server, const char *id,
01444 const char *model_type, int model_id, int parent_model_id);
01445
01447 extern int gz_stereo_destroy(gz_stereo_t *self);
01448
01450 extern int gz_stereo_open(gz_stereo_t *self, gz_client_t *client, const char *id);
01451
01453 extern int gz_stereo_close(gz_stereo_t *self);
01454
01457 extern int gz_stereo_lock(gz_stereo_t *self, int blocking);
01458
01460 extern void gz_stereo_unlock(gz_stereo_t *self);
01461
01463 extern int gz_stereo_post(gz_stereo_t *self);
01464
01466
01467
01468
01469
01470
01473
01482
01483 typedef struct gz_truth_data
01484 {
01486 gz_data_t head;
01487
01489 double time;
01490
01492 double pos[3];
01493
01495 double rot[3];
01496
01498 int cmd_new;
01499
01501 double cmd_pos[3];
01502
01504 double cmd_rot[3];
01505
01506 } gz_truth_data_t;
01507
01508
01510 typedef struct gz_truth
01511 {
01513 gz_iface_t *iface;
01514
01516 gz_truth_data_t *data;
01517
01518 } gz_truth_t;
01519
01520
01522 extern gz_truth_t *gz_truth_alloc();
01523
01525 extern void gz_truth_free(gz_truth_t *self);
01526
01528 extern int gz_truth_create(gz_truth_t *self, gz_server_t *server, const char *id,
01529 const char *model_type, int model_id, int parent_model_id);
01530
01532 extern int gz_truth_destroy(gz_truth_t *self);
01533
01535 extern int gz_truth_open(gz_truth_t *self, gz_client_t *client, const char *id);
01536
01538 extern int gz_truth_close(gz_truth_t *self);
01539
01542 extern int gz_truth_lock(gz_truth_t *self, int blocking);
01543
01545 extern void gz_truth_unlock(gz_truth_t *self);
01546
01548 extern int gz_truth_post(gz_truth_t *self);
01549
01551
01552
01553
01554
01557
01564 #define GAZEBO_WIFI_MAX_LINKS 16
01565
01567 #define GAZEBO_WIFI_QUAL_DBM 1
01568
01570 typedef struct gz_wifi_link
01571 {
01573 char ip[32];
01574
01578 uint16_t qual, level, noise;
01579
01580 } gz_wifi_link_t;
01581
01582
01583 typedef struct gz_wifi_data
01584 {
01586 gz_data_t head;
01587
01589 double time;
01590
01593 gz_wifi_link_t links[GAZEBO_WIFI_MAX_LINKS];
01594 uint16_t link_count;
01596
01597 } gz_wifi_data_t;
01598
01599
01601 typedef struct gz_wifi
01602 {
01604 gz_iface_t *iface;
01605
01607 gz_wifi_data_t *data;
01608
01609 } gz_wifi_t;
01610
01611
01613 extern gz_wifi_t *gz_wifi_alloc();
01614
01616 extern void gz_wifi_free(gz_wifi_t *self);
01617
01619 extern int gz_wifi_create(gz_wifi_t *self, gz_server_t *server, const char *id,
01620 const char *model_type, int model_id, int parent_model_id);
01621
01623 extern int gz_wifi_destroy(gz_wifi_t *self);
01624
01626 extern int gz_wifi_open(gz_wifi_t *self, gz_client_t *client, const char *id);
01627
01629 extern int gz_wifi_close(gz_wifi_t *self);
01630
01633 extern int gz_wifi_lock(gz_wifi_t *self, int blocking);
01634
01636 extern void gz_wifi_unlock(gz_wifi_t *self);
01637
01639
01640
01641
01642
01643
01644 #ifdef __cplusplus
01645 }
01646 #endif
01647
01648 #endif