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 0x060
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 #define GAZEBO_CAMERA_MAX_IMAGE_SIZE 640 * 480 * 3
00411
00413 typedef struct gz_camera_data
00414 {
00416 gz_data_t head;
00417
00419 double time;
00420
00422 unsigned int width, height;
00423
00425 unsigned int image_size;
00426 unsigned char image[GAZEBO_CAMERA_MAX_IMAGE_SIZE];
00427
00428 } gz_camera_data_t;
00429
00430
00432 typedef struct gz_camera
00433 {
00435 gz_iface_t *iface;
00436
00438 gz_camera_data_t *data;
00439
00440 } gz_camera_t;
00441
00442
00444 extern gz_camera_t *gz_camera_alloc();
00445
00447 extern void gz_camera_free(gz_camera_t *self);
00448
00450 extern int gz_camera_create(gz_camera_t *self, gz_server_t *server, const char *id,
00451 const char *model_type, int model_id, int parent_model_id);
00452
00454 extern int gz_camera_destroy(gz_camera_t *self);
00455
00457 extern int gz_camera_open(gz_camera_t *self, gz_client_t *client, const char *id);
00458
00460 extern int gz_camera_close(gz_camera_t *self);
00461
00464 extern int gz_camera_lock(gz_camera_t *self, int blocking);
00465
00467 extern void gz_camera_unlock(gz_camera_t *self);
00468
00470 extern int gz_camera_post(gz_camera_t *self);
00471
00473
00474
00475
00476
00479
00487
00488 typedef struct gz_factory_data
00489 {
00491 gz_data_t head;
00492
00494 double time;
00495
00497 uint8_t string[4096];
00498
00499 } gz_factory_data_t;
00500
00501
00503 typedef struct gz_factory
00504 {
00506 gz_iface_t *iface;
00507
00509 gz_factory_data_t *data;
00510
00511 } gz_factory_t;
00512
00513
00515 extern gz_factory_t *gz_factory_alloc();
00516
00518 extern void gz_factory_free(gz_factory_t *self);
00519
00521 extern int gz_factory_create(gz_factory_t *self, gz_server_t *server, const char *id,
00522 const char *model_type, int model_id, int parent_model_id);
00523
00525 extern int gz_factory_destroy(gz_factory_t *self);
00526
00528 extern int gz_factory_open(gz_factory_t *self, gz_client_t *client, const char *id);
00529
00531 extern int gz_factory_close(gz_factory_t *self);
00532
00535 extern int gz_factory_lock(gz_factory_t *self, int blocking);
00536
00538 extern void gz_factory_unlock(gz_factory_t *self);
00539
00541
00542
00543
00544
00547
00557 #define GZ_FIDUCIAL_MAX_FIDS 401
00558
00560 typedef struct gz_fiducial_fid
00561 {
00563 int id;
00564
00566 double pos[3];
00567
00569 double rot[3];
00570
00571 } gz_fiducial_fid_t;
00572
00573
00575 typedef struct gz_fiducial_data
00576 {
00578 gz_data_t head;
00579
00581 double time;
00582
00584 int fid_count;
00585 gz_fiducial_fid_t fids[GZ_FIDUCIAL_MAX_FIDS];
00586
00587 } gz_fiducial_data_t;
00588
00589
00591 typedef struct gz_fiducial
00592 {
00594 gz_iface_t *iface;
00595
00597 gz_fiducial_data_t *data;
00598
00599 } gz_fiducial_t;
00600
00601
00603 extern gz_fiducial_t *gz_fiducial_alloc();
00604
00606 extern void gz_fiducial_free(gz_fiducial_t *self);
00607
00609 extern int gz_fiducial_create(gz_fiducial_t *self, gz_server_t *server, const char *id,
00610 const char *model_type, int model_id, int parent_model_id);
00611
00613 extern int gz_fiducial_destroy(gz_fiducial_t *self);
00614
00616 extern int gz_fiducial_open(gz_fiducial_t *self, gz_client_t *client, const char *id);
00617
00619 extern int gz_fiducial_close(gz_fiducial_t *self);
00620
00623 extern int gz_fiducial_lock(gz_fiducial_t *self, int blocking);
00624
00626 extern void gz_fiducial_unlock(gz_fiducial_t *self);
00627
00629 extern int gz_fiducial_post(gz_fiducial_t *self);
00630
00632
00633
00634
00635
00638
00647
00648 #define GAZEBO_GUICAM_MAX_IMAGE_SIZE 1024 * 768 * 3
00649
00651 typedef struct gz_guicam_data
00652 {
00654 gz_data_t head;
00655
00657 double sim_time;
00658
00661 double pause_time;
00662
00664 double pos[3];
00665
00667 double rot[3];
00668
00670 int cmd_spot_mode;
00671
00673 int cmd_spot_state;
00674
00676 double cmd_spot_a[2], cmd_spot_b[2];
00677
00680 int roll_lock;
00681
00683 int display_bbox;
00684
00686 int display_axes;
00687
00689 int display_com;
00690
00692 int display_skins;
00693
00695 int display_rays;
00696
00698 int display_frustrums;
00699
00701 int display_materials;
00702
00704 int display_textures;
00705
00707 int polygon_fill;
00708
00710 int shade_smooth;
00711
00713 int save_frames;
00714
00716 unsigned int width, height;
00717
00719 unsigned char image[GAZEBO_GUICAM_MAX_IMAGE_SIZE];
00720 unsigned int image_size;
00721
00722 } gz_guicam_data_t;
00723
00724
00726 typedef struct gz_guicam
00727 {
00729 gz_iface_t *iface;
00730
00732 gz_guicam_data_t *data;
00733
00734 } gz_guicam_t;
00735
00736
00738 extern gz_guicam_t *gz_guicam_alloc();
00739
00741 extern void gz_guicam_free(gz_guicam_t *self);
00742
00744 extern int gz_guicam_create(gz_guicam_t *self, gz_server_t *server, const char *id,
00745 const char *model_type, int model_id, int parent_model_id);
00746
00748 extern int gz_guicam_destroy(gz_guicam_t *self);
00749
00751 extern int gz_guicam_open(gz_guicam_t *self, gz_client_t *client, const char *id);
00752
00754 extern int gz_guicam_close(gz_guicam_t *self);
00755
00758 extern int gz_guicam_lock(gz_guicam_t *self, int blocking);
00759
00761 extern void gz_guicam_unlock(gz_guicam_t *self);
00762
00764 extern int gz_guicam_post(gz_guicam_t *self);
00765
00767
00768
00769
00770
00773
00782
00783 typedef struct gz_gps_data
00784 {
00786 gz_data_t head;
00787
00789 double time;
00790
00792 double utc_time;
00793
00795 double latitude;
00796
00798 double longitude;
00799
00801 double altitude;
00802
00804 double utm_e, utm_n;
00805
00807 int satellites;
00808
00810 int quality;
00811
00813 double hdop;
00814
00816 double vdop;
00817
00819 double err_horz, err_vert;
00820
00821 } gz_gps_data_t;
00822
00823
00825 typedef struct gz_gps
00826 {
00828 gz_iface_t *iface;
00829
00831 gz_gps_data_t *data;
00832
00833 } gz_gps_t;
00834
00835
00837 extern gz_gps_t *gz_gps_alloc();
00838
00840 extern void gz_gps_free(gz_gps_t *self);
00841
00843 extern int gz_gps_create(gz_gps_t *self, gz_server_t *server, const char *id,
00844 const char *model_type, int model_id, int parent_model_id);
00845
00847 extern int gz_gps_destroy(gz_gps_t *self);
00848
00850 extern int gz_gps_open(gz_gps_t *self, gz_client_t *client, const char *id);
00851
00853 extern int gz_gps_close(gz_gps_t *self);
00854
00857 extern int gz_gps_lock(gz_gps_t *self, int blocking);
00858
00860 extern void gz_gps_unlock(gz_gps_t *self);
00861
00863 extern int gz_gps_post(gz_gps_t *self);
00864
00866
00867
00868
00869
00870
00873
00881
00882 typedef struct gz_gripper_data
00883 {
00885 gz_data_t head;
00886
00888 double time;
00889
00890 int cmd;
00891 int lift_limit_reach;
00892 int grip_limit_reach;
00893 int outer_beam_obstruct;
00894 int inner_beam_obstruct;
00895 int left_paddle_open;
00896 int right_paddle_open;
00897 int paddles_opened;
00898 int paddles_closed;
00899 int paddles_moving;
00900 int paddles_error;
00901 int lift_up;
00902 int lift_down;
00903 int lift_moving;
00904 int lift_error;
00905
00906 } gz_gripper_data_t;
00907
00908
00910 typedef struct gz_gripper
00911 {
00913 gz_iface_t *iface;
00914
00916 gz_gripper_data_t *data;
00917
00918 } gz_gripper_t;
00919
00920
00922 extern gz_gripper_t *gz_gripper_alloc();
00923
00925 extern void gz_gripper_free(gz_gripper_t *self);
00926
00928 extern int gz_gripper_create(gz_gripper_t *self, gz_server_t *server, const char *id,
00929 const char *model_type, int model_id, int parent_model_id);
00930
00932 extern int gz_gripper_destroy(gz_gripper_t *self);
00933
00935 extern int gz_gripper_open(gz_gripper_t *self, gz_client_t *client, const char *id);
00936
00938 extern int gz_gripper_close(gz_gripper_t *self);
00939
00942 extern int gz_gripper_lock(gz_gripper_t *self, int blocking);
00943
00945 extern void gz_gripper_unlock(gz_gripper_t *self);
00946
00948
00949
00950
00951
00954
00963 #define GZ_LASER_MAX_RANGES 401
00964
00966 typedef struct gz_laser_data
00967 {
00969 gz_data_t head;
00970
00972 double time;
00973
00975 double min_angle, max_angle;
00976
00978 double res_angle;
00979
00981 double max_range;
00982
00984 int range_count;
00985
00987 double ranges[GZ_LASER_MAX_RANGES];
00988
00990 int intensity[GZ_LASER_MAX_RANGES];
00991
00992
00993 int cmd_new_angle;
00994 int cmd_new_length;
00995
00996
00997 double cmd_max_range;
00998 double cmd_min_angle, cmd_max_angle;
00999 int cmd_range_count;
01000
01001 } gz_laser_data_t;
01002
01003
01005 typedef struct gz_laser
01006 {
01008 gz_iface_t *iface;
01009
01011 gz_laser_data_t *data;
01012
01013 } gz_laser_t;
01014
01015
01017 extern gz_laser_t *gz_laser_alloc();
01018
01020 extern void gz_laser_free(gz_laser_t *self);
01021
01023 extern int gz_laser_create(gz_laser_t *self, gz_server_t *server, const char *id,
01024 const char *model_type, int model_id, int parent_model_id);
01025
01027 extern int gz_laser_destroy(gz_laser_t *self);
01028
01030 extern int gz_laser_open(gz_laser_t *self, gz_client_t *client, const char *id);
01031
01033 extern int gz_laser_close(gz_laser_t *self);
01034
01037 extern int gz_laser_lock(gz_laser_t *self, int blocking);
01038
01040 extern void gz_laser_unlock(gz_laser_t *self);
01041
01043 extern int gz_laser_post(gz_laser_t *self);
01044
01046
01047
01048
01049
01052
01061
01062 typedef struct gz_position_data
01063 {
01065 gz_data_t head;
01066
01068 double time;
01069
01071 double pos[3];
01072 double rot[3];
01073
01075 double vel_pos[3];
01076 double vel_rot[3];
01077
01079 int stall;
01080
01082 int cmd_enable_motors;
01083
01085 double cmd_vel_pos[3];
01086 double cmd_vel_rot[3];
01087
01088 } gz_position_data_t;
01089
01090
01092 typedef struct gz_position
01093 {
01095 gz_iface_t *iface;
01096
01098 gz_position_data_t *data;
01099
01100 } gz_position_t;
01101
01102
01104 extern gz_position_t *gz_position_alloc();
01105
01107 extern void gz_position_free(gz_position_t *self);
01108
01110 extern int gz_position_create(gz_position_t *self, gz_server_t *server, const char *id,
01111 const char *model_type, int model_id, int parent_model_id);
01112
01114 extern int gz_position_destroy(gz_position_t *self);
01115
01117 extern int gz_position_open(gz_position_t *self, gz_client_t *client, const char *id);
01118
01120 extern int gz_position_close(gz_position_t *self);
01121
01124 extern int gz_position_lock(gz_position_t *self, int blocking);
01125
01127 extern void gz_position_unlock(gz_position_t *self);
01128
01130 extern int gz_position_post(gz_position_t *self);
01131
01133
01134
01135
01136
01139
01147
01148 typedef struct gz_power_data
01149 {
01151 gz_data_t head;
01152
01154 double time;
01155
01157 double levels[10];
01158
01159 } gz_power_data_t;
01160
01161
01163 typedef struct gz_power
01164 {
01166 gz_iface_t *iface;
01167
01169 gz_power_data_t *data;
01170
01171 } gz_power_t;
01172
01173
01175 extern gz_power_t *gz_power_alloc();
01176
01178 extern void gz_power_free(gz_power_t *self);
01179
01181 extern int gz_power_create(gz_power_t *self, gz_server_t *server, const char *id,
01182 const char *model_type, int model_id, int parent_model_id);
01183
01185 extern int gz_power_destroy(gz_power_t *self);
01186
01188 extern int gz_power_open(gz_power_t *self, gz_client_t *client, const char *id);
01189
01191 extern int gz_power_close(gz_power_t *self);
01192
01195 extern int gz_power_lock(gz_power_t *self, int blocking);
01196
01198 extern void gz_power_unlock(gz_power_t *self);
01199
01201 extern int gz_power_post(gz_power_t *self);
01202
01204
01205
01206
01207
01210
01218
01219 typedef struct gz_ptz_data
01220 {
01222 gz_data_t head;
01223
01225 double time;
01226
01228 double pan, tilt;
01229
01231 double zoom;
01232
01234 double cmd_pan, cmd_tilt;
01235
01237 double cmd_zoom;
01238
01239 } gz_ptz_data_t;
01240
01241
01243 typedef struct gz_ptz
01244 {
01246 gz_data_t head;
01247
01249 gz_iface_t *iface;
01250
01252 gz_ptz_data_t *data;
01253
01254 } gz_ptz_t;
01255
01256
01258 extern gz_ptz_t *gz_ptz_alloc();
01259
01261 extern void gz_ptz_free(gz_ptz_t *self);
01262
01264 extern int gz_ptz_create(gz_ptz_t *self, gz_server_t *server, const char *id,
01265 const char *model_type, int model_id, int parent_model_id);
01266
01268 extern int gz_ptz_destroy(gz_ptz_t *self);
01269
01271 extern int gz_ptz_open(gz_ptz_t *self, gz_client_t *client, const char *id);
01272
01274 extern int gz_ptz_close(gz_ptz_t *self);
01275
01278 extern int gz_ptz_lock(gz_ptz_t *self, int blocking);
01279
01281 extern void gz_ptz_unlock(gz_ptz_t *self);
01282
01284 extern int gz_ptz_post(gz_ptz_t *self);
01285
01286
01288
01289
01290
01291
01294
01302 #define GZ_SONAR_MAX_RANGES 48
01303
01305 typedef struct gz_sonar_data
01306 {
01308 gz_data_t head;
01309
01311 double time;
01312
01314 double max_range;
01315
01317 int sonar_count;
01318
01320 double sonar_pos[GZ_SONAR_MAX_RANGES][3];
01321
01323 double sonar_rot[GZ_SONAR_MAX_RANGES][3];
01324
01326 double sonar_ranges[GZ_SONAR_MAX_RANGES];
01327
01329 int cmd_enable_sonar;
01330
01331 } gz_sonar_data_t;
01332
01333
01335 typedef struct gz_sonar
01336 {
01338 gz_iface_t *iface;
01339
01341 gz_sonar_data_t *data;
01342
01343 } gz_sonar_t;
01344
01345
01347 extern gz_sonar_t *gz_sonar_alloc();
01348
01350 extern void gz_sonar_free(gz_sonar_t *self);
01351
01353 extern int gz_sonar_create(gz_sonar_t *self, gz_server_t *server, const char *id,
01354 const char *model_type, int model_id, int parent_model_id);
01355
01357 extern int gz_sonar_destroy(gz_sonar_t *self);
01358
01360 extern int gz_sonar_open(gz_sonar_t *self, gz_client_t *client, const char *id);
01361
01363 extern int gz_sonar_close(gz_sonar_t *self);
01364
01367 extern int gz_sonar_lock(gz_sonar_t *self, int blocking);
01368
01370 extern void gz_sonar_unlock(gz_sonar_t *self);
01371
01373
01374
01375
01376
01379
01388
01389 #define GAZEBO_STEREO_MAX_RGB_SIZE 640 * 480 * 3
01390 #define GAZEBO_STEREO_MAX_DISPARITY_SIZE 640 * 480
01391
01393 typedef struct gz_stereo_data
01394 {
01396 gz_data_t head;
01397
01399 double time;
01400
01402 unsigned int width, height;
01403
01405 unsigned int left_image_size;
01406 unsigned char left_image[GAZEBO_STEREO_MAX_RGB_SIZE];
01407
01409 unsigned int right_image_size;
01410 unsigned char right_image[GAZEBO_STEREO_MAX_RGB_SIZE];
01411
01413 unsigned int left_disparity_size;
01414 float left_disparity[GAZEBO_STEREO_MAX_DISPARITY_SIZE];
01415
01417 unsigned int right_disparity_size;
01418 float right_disparity[GAZEBO_STEREO_MAX_DISPARITY_SIZE];
01419
01420 } gz_stereo_data_t;
01421
01422
01424 typedef struct gz_stereo
01425 {
01427 gz_iface_t *iface;
01428
01430 gz_stereo_data_t *data;
01431
01432 } gz_stereo_t;
01433
01434
01436 extern gz_stereo_t *gz_stereo_alloc();
01437
01439 extern void gz_stereo_free(gz_stereo_t *self);
01440
01442 extern int gz_stereo_create(gz_stereo_t *self, gz_server_t *server, const char *id,
01443 const char *model_type, int model_id, int parent_model_id);
01444
01446 extern int gz_stereo_destroy(gz_stereo_t *self);
01447
01449 extern int gz_stereo_open(gz_stereo_t *self, gz_client_t *client, const char *id);
01450
01452 extern int gz_stereo_close(gz_stereo_t *self);
01453
01456 extern int gz_stereo_lock(gz_stereo_t *self, int blocking);
01457
01459 extern void gz_stereo_unlock(gz_stereo_t *self);
01460
01462 extern int gz_stereo_post(gz_stereo_t *self);
01463
01465
01466
01467
01468
01469
01472
01481
01482 typedef struct gz_truth_data
01483 {
01485 gz_data_t head;
01486
01488 double time;
01489
01491 double pos[3];
01492
01494 double rot[4];
01495
01497 int cmd_new;
01498
01500 double cmd_pos[3];
01501
01503 double cmd_rot[4];
01504
01505 } gz_truth_data_t;
01506
01507
01509 typedef struct gz_truth
01510 {
01512 gz_iface_t *iface;
01513
01515 gz_truth_data_t *data;
01516
01517 } gz_truth_t;
01518
01519
01521 extern gz_truth_t *gz_truth_alloc();
01522
01524 extern void gz_truth_free(gz_truth_t *self);
01525
01527 extern int gz_truth_create(gz_truth_t *self, gz_server_t *server, const char *id,
01528 const char *model_type, int model_id, int parent_model_id);
01529
01531 extern int gz_truth_destroy(gz_truth_t *self);
01532
01534 extern int gz_truth_open(gz_truth_t *self, gz_client_t *client, const char *id);
01535
01537 extern int gz_truth_close(gz_truth_t *self);
01538
01541 extern int gz_truth_lock(gz_truth_t *self, int blocking);
01542
01544 extern void gz_truth_unlock(gz_truth_t *self);
01545
01547 extern int gz_truth_post(gz_truth_t *self);
01548
01550 extern void gz_truth_euler_from_quatern(gz_truth_t *self, double *e, double *q);
01551
01553 extern void gz_truth_quatern_from_euler(gz_truth_t *self, double *q, double *e);
01554
01556
01557
01558
01559
01562
01569 #define GAZEBO_WIFI_MAX_LINKS 16
01570
01572 #define GAZEBO_WIFI_QUAL_DBM 1
01573
01575 typedef struct gz_wifi_link
01576 {
01578 char ip[32];
01579
01583 uint16_t qual, level, noise;
01584
01585 } gz_wifi_link_t;
01586
01587
01588 typedef struct gz_wifi_data
01589 {
01591 gz_data_t head;
01592
01594 double time;
01595
01598 gz_wifi_link_t links[GAZEBO_WIFI_MAX_LINKS];
01599 uint16_t link_count;
01601
01602 } gz_wifi_data_t;
01603
01604
01606 typedef struct gz_wifi
01607 {
01609 gz_iface_t *iface;
01610
01612 gz_wifi_data_t *data;
01613
01614 } gz_wifi_t;
01615
01616
01618 extern gz_wifi_t *gz_wifi_alloc();
01619
01621 extern void gz_wifi_free(gz_wifi_t *self);
01622
01624 extern int gz_wifi_create(gz_wifi_t *self, gz_server_t *server, const char *id,
01625 const char *model_type, int model_id, int parent_model_id);
01626
01628 extern int gz_wifi_destroy(gz_wifi_t *self);
01629
01631 extern int gz_wifi_open(gz_wifi_t *self, gz_client_t *client, const char *id);
01632
01634 extern int gz_wifi_close(gz_wifi_t *self);
01635
01638 extern int gz_wifi_lock(gz_wifi_t *self, int blocking);
01639
01641 extern void gz_wifi_unlock(gz_wifi_t *self);
01642
01644
01645
01646
01647
01650
01659 #define GAZEBO_JOINT_MAX_JOINTS 20
01660
01662 typedef struct gz_joint_data
01663 {
01665 int type;
01666
01668 double anchor[3];
01669
01671 double axis[3];
01672
01674 double axis2[3];
01675
01677 double angular_velocity;
01678
01680 double angular_velocity2;
01681
01683 double angle;
01684
01686 double angle2;
01687
01689 double cmd_angle;
01690
01692 double cmd_angle2;
01693
01694 } gz_joint_data_t;
01695
01697 typedef struct gz_joints
01698 {
01700 gz_data_t head;
01701
01703 double time;
01704
01705 gz_joint_data_t joints[GAZEBO_JOINT_MAX_JOINTS];
01706
01707 int joint_count;
01708
01709 } gz_joints_t;
01710
01711
01713 typedef struct gz_joint
01714 {
01716 gz_iface_t *iface;
01717
01719 gz_joints_t *data;
01720
01721 } gz_joint_t;
01722
01723
01725 extern gz_joint_t *gz_joint_alloc();
01726
01728 extern void gz_joint_free(gz_joint_t *self);
01729
01731 extern int gz_joint_create(gz_joint_t *self, gz_server_t *server, const char *id, const char *model_type, int model_id, int parent_model_id);
01732
01734 extern int gz_joint_destroy(gz_joint_t *self);
01735
01737 extern int gz_joint_open(gz_joint_t *self, gz_client_t *client, const char *id);
01738
01740 extern int gz_joint_close(gz_joint_t *self);
01741
01744 extern int gz_joint_lock(gz_joint_t *self, int blocking);
01745
01747 extern void gz_joint_unlock(gz_joint_t *self);
01748
01750 extern int gz_joint_post(gz_joint_t *self);
01751
01753
01754
01755
01756
01757
01758 #ifdef __cplusplus
01759 }
01760 #endif
01761
01762 #endif