Gazebo logo

gazebo.h

Go to the documentation of this file.
00001 /*
00002  *  Gazebo - Outdoor Multi-Robot Simulator
00003  *  Copyright (C) 2003  
00004  *     Nate Koenig & Andrew Howard
00005  *
00006  *  This program is free software; you can redistribute it and/or modify
00007  *  it under the terms of the GNU General Public License as published by
00008  *  the Free Software Foundation; either version 2 of the License, or
00009  *  (at your option) any later version.
00010  *
00011  *  This program is distributed in the hope that it will be useful,
00012  *  but WITHOUT ANY WARRANTY; without even the implied warranty of
00013  *  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00014  *  GNU General Public License for more details.
00015  *
00016  *  You should have received a copy of the GNU General Public License
00017  *  along with this program; if not, write to the Free Software
00018  *  Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
00019  *
00020  */
00021 
00022 /* Desc: External interfaces for Gazebo
00023  * Author: Andrew Howard
00024  * Date: 6 Apr 2003
00025  * CVS: $Id: gazebo.h,v 1.87 2006/11/02 17:06:31 natepak Exp $
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  * Constants, etc
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   // The server we are associated with
00257   gz_server_t *server;
00258   
00259   // The client we are associated with
00260   gz_client_t *client;
00261   
00262   // File descriptor for the mmap file
00263   int mmap_fd;
00264 
00265   // Pointer to the mmap'ed mem
00266   void *mmap;
00267 
00268   // The name of the file we created/opened
00269   char *filename;
00270   
00271 } gz_iface_t;
00272 
00273 
00274 // Create an interface
00275 extern gz_iface_t *gz_iface_alloc();
00276 
00277 // @internal Destroy an interface
00278 extern void gz_iface_free(gz_iface_t *self);
00279 
00280 // @internal Create the interface (used by Gazebo server)
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 // @internal Destroy the interface (server)
00285 extern int gz_iface_destroy(gz_iface_t *self);
00286 
00287 // Open an existing interface
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 // Close the interface
00292 extern int gz_iface_close(gz_iface_t *self);
00293 
00294 // Lock the interface.  Set blocking to 1 if the caller should block
00295 // until the lock is acquired.  Returns 0 if the lock is acquired.
00296 extern int gz_iface_lock(gz_iface_t *self, int blocking);
00297 
00298 // Unlock the interface
00299 extern void gz_iface_unlock(gz_iface_t *self);
00300 
00301 // Tell clients that new data is available
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   // Elapsed real time since start of simulation (from system clock). 
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 
00882 #define GAZEBO_GRIPPER_STATE_OPEN 1
00883 
00884 #define GAZEBO_GRIPPER_STATE_CLOSED 2
00885 
00886 #define GAZEBO_GRIPPER_STATE_MOVING 3
00887 
00888 #define GAZEBO_GRIPPER_STATE_ERROR 4
00889 
00891 #define GAZEBO_GRIPPER_CMD_OPEN 1
00892 
00893 #define GAZEBO_GRIPPER_CMD_CLOSE 2
00894 
00895 #define GAZEBO_GRIPPER_CMD_STOP 3
00896 
00897 #define GAZEBO_GRIPPER_CMD_STORE 4
00898 
00899 #define GAZEBO_GRIPPER_CMD_RETRIEVE 5
00900 
00902 typedef struct gz_gripper_data
00903 {
00905   gz_data_t head;
00906 
00908   double time;
00909  
00911   int cmd;
00912 
00914   int state;
00915 
00916   int grip_limit_reach;
00917   int lift_limit_reach;
00918   int outer_beam_obstruct;
00919   int inner_beam_obstruct;
00920   int left_paddle_open;
00921   int right_paddle_open;
00922 
00923   int lift_up;
00924   int lift_down;
00925 
00926 } gz_gripper_data_t;
00927 
00928 
00930 typedef struct gz_gripper
00931 {
00933   gz_iface_t *iface;
00934 
00936   gz_gripper_data_t *data;
00937   
00938 } gz_gripper_t;
00939 
00940 
00942 extern gz_gripper_t *gz_gripper_alloc();
00943 
00945 extern void gz_gripper_free(gz_gripper_t *self);
00946 
00948 extern int gz_gripper_create(gz_gripper_t *self, gz_server_t *server, const char *id,
00949                              const char *model_type, int model_id, int parent_model_id);
00950 
00952 extern int gz_gripper_destroy(gz_gripper_t *self);
00953 
00955 extern int gz_gripper_open(gz_gripper_t *self, gz_client_t *client, const char *id);
00956 
00958 extern int gz_gripper_close(gz_gripper_t *self);
00959 
00962 extern int gz_gripper_lock(gz_gripper_t *self, int blocking);
00963 
00965 extern void gz_gripper_unlock(gz_gripper_t *self);
00966 
00968 
00969 
00970 
00971 /***************************************************************************/
00974 
00983 #define GZ_LASER_MAX_RANGES 401
00984 
00986 typedef struct gz_laser_data
00987 {
00989   gz_data_t head;
00990 
00992   double time;
00993   
00995   double min_angle, max_angle;
00996 
00998   double res_angle;
00999 
01001   double max_range;
01002 
01004   int range_count;
01005   
01007   double ranges[GZ_LASER_MAX_RANGES];
01008 
01010   int intensity[GZ_LASER_MAX_RANGES];
01011   
01012   // New command ( 0 or 1 )
01013   int cmd_new_angle;
01014   int cmd_new_length;
01015 
01016   // Commanded range value
01017   double cmd_max_range;
01018   double cmd_min_angle, cmd_max_angle;
01019   int cmd_range_count;
01020 
01021 } gz_laser_data_t;
01022 
01023 
01025 typedef struct gz_laser
01026 {
01028   gz_iface_t *iface;
01029 
01031   gz_laser_data_t *data;
01032   
01033 } gz_laser_t;
01034 
01035 
01037 extern gz_laser_t *gz_laser_alloc();
01038 
01040 extern void gz_laser_free(gz_laser_t *self);
01041 
01043 extern int gz_laser_create(gz_laser_t *self, gz_server_t *server, const char *id,
01044                            const char *model_type, int model_id, int parent_model_id);
01045 
01047 extern int gz_laser_destroy(gz_laser_t *self);
01048 
01050 extern int gz_laser_open(gz_laser_t *self, gz_client_t *client, const char *id);
01051 
01053 extern int gz_laser_close(gz_laser_t *self);
01054 
01057 extern int gz_laser_lock(gz_laser_t *self, int blocking);
01058 
01060 extern void gz_laser_unlock(gz_laser_t *self);
01061 
01063 extern int gz_laser_post(gz_laser_t *self);
01064 
01066 
01067 
01068 
01069 /***************************************************************************/
01072 
01081 
01082 typedef struct gz_position_data
01083 {
01085   gz_data_t head;
01086 
01088   double time;
01089 
01091   double pos[3];
01092   double rot[3];
01093 
01095   double vel_pos[3];
01096   double vel_rot[3];
01097 
01099   int stall;
01100 
01102   int cmd_enable_motors;
01103   
01105   double cmd_vel_pos[3];
01106   double cmd_vel_rot[3];
01107   
01108 } gz_position_data_t;
01109 
01110 
01112 typedef struct gz_position
01113 {
01115   gz_iface_t *iface;
01116 
01118   gz_position_data_t *data;
01119   
01120 } gz_position_t;
01121 
01122 
01124 extern gz_position_t *gz_position_alloc();
01125 
01127 extern void gz_position_free(gz_position_t *self);
01128 
01130 extern int gz_position_create(gz_position_t *self, gz_server_t *server, const char *id,
01131                               const char *model_type, int model_id, int parent_model_id);
01132 
01134 extern int gz_position_destroy(gz_position_t *self);
01135 
01137 extern int gz_position_open(gz_position_t *self, gz_client_t *client, const char *id);
01138 
01140 extern int gz_position_close(gz_position_t *self);
01141 
01144 extern int gz_position_lock(gz_position_t *self, int blocking);
01145 
01147 extern void gz_position_unlock(gz_position_t *self);
01148 
01150 extern int gz_position_post(gz_position_t *self);
01151 
01153 
01154 
01155 
01156 /***************************************************************************/
01159 
01167 
01168 typedef struct gz_power_data
01169 {
01171   gz_data_t head;
01172 
01174   double time;
01175 
01177   double levels[10];
01178   
01179 } gz_power_data_t;
01180 
01181 
01183 typedef struct gz_power
01184 {
01186   gz_iface_t *iface;
01187 
01189   gz_power_data_t *data;
01190   
01191 } gz_power_t;
01192 
01193 
01195 extern gz_power_t *gz_power_alloc();
01196 
01198 extern void gz_power_free(gz_power_t *self);
01199 
01201 extern int gz_power_create(gz_power_t *self, gz_server_t *server, const char *id,
01202                            const char *model_type, int model_id, int parent_model_id);
01203 
01205 extern int gz_power_destroy(gz_power_t *self);
01206 
01208 extern int gz_power_open(gz_power_t *self, gz_client_t *client, const char *id);
01209 
01211 extern int gz_power_close(gz_power_t *self);
01212 
01215 extern int gz_power_lock(gz_power_t *self, int blocking);
01216 
01218 extern void gz_power_unlock(gz_power_t *self);
01219 
01221 extern int gz_power_post(gz_power_t *self);
01222 
01224 
01225 
01226 
01227 /***************************************************************************/
01230 
01238 
01239 typedef struct gz_ptz_data
01240 {
01242   gz_data_t head;
01243   
01245   double time;
01246 
01248   double pan, tilt;
01249 
01251   double zoom;
01252 
01254   double cmd_pan, cmd_tilt;
01255 
01257   double cmd_zoom;
01258   
01259 } gz_ptz_data_t;
01260 
01261 
01263 typedef struct gz_ptz
01264 {
01266   gz_data_t head;
01267   
01269   gz_iface_t *iface;
01270 
01272   gz_ptz_data_t *data;
01273   
01274 } gz_ptz_t;
01275 
01276 
01278 extern gz_ptz_t *gz_ptz_alloc();
01279 
01281 extern void gz_ptz_free(gz_ptz_t *self);
01282 
01284 extern int gz_ptz_create(gz_ptz_t *self, gz_server_t *server, const char *id,
01285                          const char *model_type, int model_id, int parent_model_id);
01286 
01288 extern int gz_ptz_destroy(gz_ptz_t *self);
01289 
01291 extern int gz_ptz_open(gz_ptz_t *self, gz_client_t *client, const char *id);
01292 
01294 extern int gz_ptz_close(gz_ptz_t *self);
01295 
01298 extern int gz_ptz_lock(gz_ptz_t *self, int blocking);
01299 
01301 extern void gz_ptz_unlock(gz_ptz_t *self);
01302 
01304 extern int gz_ptz_post(gz_ptz_t *self);
01305 
01306 
01308 
01309 
01310 
01311 /***************************************************************************/
01314 
01322 #define GAZEBO_ACTARRAY_NUM_ACTUATORS 16
01323 #define GAZEBO_ACTARRAY_JOINT_POSITION_MODE 0
01324 #define GAZEBO_ACTARRAY_JOINT_SPEED_MODE 1
01325 #define GAZEBO_ACTARRAY_JOINT_CURRENT_MODE 2
01326 
01328 #define GAZEBO_ACTARRAY_ACTSTATE_IDLE     1
01329 
01330 #define GAZEBO_ACTARRAY_ACTSTATE_MOVING   2
01331 
01332 #define GAZEBO_ACTARRAY_ACTSTATE_BRAKED   3
01333 
01334 #define GAZEBO_ACTARRAY_ACTSTATE_STALLED  4
01335 
01336 
01338 typedef struct gazebo_actarray_actuator
01339 {
01341   float position;
01343   float speed;
01345   uint8_t state;
01346 } gazebo_actarray_actuator_t;
01347 
01348 //TODO: Extend this for the complete interface
01350 typedef struct gz_actarray_data
01351 {
01353   gz_data_t head;
01354   
01356   double time;
01357   
01358   // Timestamp for commands;
01359   unsigned int new_cmd;
01360 
01362   uint32_t actuators_count;
01364   gazebo_actarray_actuator_t actuators_data[GAZEBO_ACTARRAY_NUM_ACTUATORS];
01365   //gazebo_actarray_actuatorgeom_t actuators_geom[GAZEBO_ACTARRAY_NUM_ACTUATORS];
01367   //gazebo_point_3d_t base_pos;
01369   //gazebo_orientation_3d_t base_orientation;  
01370    float cmd_pos[GAZEBO_ACTARRAY_NUM_ACTUATORS];
01371    float cmd_speed[GAZEBO_ACTARRAY_NUM_ACTUATORS];
01372    float cmd_current[GAZEBO_ACTARRAY_NUM_ACTUATORS];
01373    unsigned int joint_mode[GAZEBO_ACTARRAY_NUM_ACTUATORS];  //Position/Speed/Current mode
01374 
01375 } gz_actarray_data_t;
01376 
01377 
01379 typedef struct gz_actarray
01380 {
01382   gz_data_t head;
01383   
01385   gz_iface_t *iface;
01386 
01388   gz_actarray_data_t *data;
01389   
01390 } gz_actarray_t;
01391 
01392 
01394 extern gz_actarray_t *gz_actarray_alloc();
01395 
01397 extern void gz_actarray_free(gz_actarray_t *self);
01398 
01400 extern int gz_actarray_create(gz_actarray_t *self, gz_server_t *server, const char *id,
01401                          const char *model_type, int model_id, int parent_model_id);
01402 
01404 extern int gz_actarray_destroy(gz_actarray_t *self);
01405 
01407 extern int gz_actarray_open(gz_actarray_t *self, gz_client_t *client, const char *id);
01408 
01410 extern int gz_actarray_close(gz_actarray_t *self);
01411 
01414 extern int gz_actarray_lock(gz_actarray_t *self, int blocking);
01415 
01417 extern void gz_actarray_unlock(gz_actarray_t *self);
01418 
01420 extern int gz_actarray_post(gz_actarray_t *self);
01421 
01422 
01424 
01425 
01426 
01427 
01428 
01429 
01430 /***************************************************************************/
01433 
01441 #define GZ_SONAR_MAX_RANGES 48
01442 
01444 typedef struct gz_sonar_data
01445 {
01447   gz_data_t head;
01448 
01450   double time;
01451 
01453   double max_range;
01454 
01456   int sonar_count;
01457 
01459   double sonar_pos[GZ_SONAR_MAX_RANGES][3];
01460 
01462   double sonar_rot[GZ_SONAR_MAX_RANGES][3];
01463 
01465   double sonar_ranges[GZ_SONAR_MAX_RANGES];
01466   
01468   int cmd_enable_sonar;
01469 
01470 } gz_sonar_data_t;
01471 
01472 
01474 typedef struct gz_sonar
01475 {
01477   gz_iface_t *iface;
01478 
01480   gz_sonar_data_t *data;
01481 
01482 } gz_sonar_t;
01483 
01484 
01486 extern gz_sonar_t *gz_sonar_alloc();
01487 
01489 extern void gz_sonar_free(gz_sonar_t *self);
01490 
01492 extern int gz_sonar_create(gz_sonar_t *self, gz_server_t *server, const char *id,
01493                            const char *model_type, int model_id, int parent_model_id);
01494 
01496 extern int gz_sonar_destroy(gz_sonar_t *self);
01497 
01499 extern int gz_sonar_open(gz_sonar_t *self, gz_client_t *client, const char *id);
01500 
01502 extern int gz_sonar_close(gz_sonar_t *self);
01503 
01506 extern int gz_sonar_lock(gz_sonar_t *self, int blocking);
01507 
01509 extern void gz_sonar_unlock(gz_sonar_t *self);
01510 
01512 
01513 //
01514 /***************************************************************************/
01517 
01525 #define GZ_IR_MAX_RANGES 48
01526 
01528 typedef struct gz_ir_data
01529 {
01531   gz_data_t head;
01532 
01534   double time;
01535 
01537   double max_range;
01538 
01540   int ir_count;
01541 
01543   double ir_pos[GZ_IR_MAX_RANGES][3];
01544 
01546   double ir_rot[GZ_IR_MAX_RANGES][3];
01547 
01549   double ir_ranges[GZ_IR_MAX_RANGES];
01550   
01552   int cmd_enable_ir;
01553 
01554 } gz_ir_data_t;
01555 
01556 
01558 typedef struct gz_ir
01559 {
01561   gz_iface_t *iface;
01562 
01564   gz_ir_data_t *data;
01565 
01566 } gz_ir_t;
01567 
01568 
01570 extern gz_ir_t *gz_ir_alloc();
01571 
01573 extern void gz_ir_free(gz_ir_t *self);
01574 
01576 extern int gz_ir_create(gz_ir_t *self, gz_server_t *server, const char *id,
01577                            const char *model_type, int model_id, int parent_model_id);
01578 
01580 extern int gz_ir_destroy(gz_ir_t *self);
01581 
01583 extern int gz_ir_open(gz_ir_t *self, gz_client_t *client, const char *id);
01584 
01586 extern int gz_ir_close(gz_ir_t *self);
01587 
01590 extern int gz_ir_lock(gz_ir_t *self, int blocking);
01591 
01593 extern void gz_ir_unlock(gz_ir_t *self);
01594 
01596 
01597 
01598 
01599 
01600 /***************************************************************************/
01603 
01612 
01613 #define GAZEBO_STEREO_MAX_RGB_SIZE 640 * 480 * 3
01614 #define GAZEBO_STEREO_MAX_DISPARITY_SIZE 640 * 480
01615 
01617 typedef struct gz_stereo_data
01618 {
01620   gz_data_t head;
01621 
01623   double time;
01624 
01626   unsigned int width, height;
01627 
01629   unsigned int left_image_size;
01630   unsigned char left_image[GAZEBO_STEREO_MAX_RGB_SIZE];
01631 
01633   unsigned int right_image_size;
01634   unsigned char right_image[GAZEBO_STEREO_MAX_RGB_SIZE];
01635 
01637   unsigned int left_disparity_size;
01638   float left_disparity[GAZEBO_STEREO_MAX_DISPARITY_SIZE];
01639 
01641   unsigned int right_disparity_size;
01642   float right_disparity[GAZEBO_STEREO_MAX_DISPARITY_SIZE];
01643 
01644 } gz_stereo_data_t;
01645 
01646 
01648 typedef struct gz_stereo
01649 {
01651   gz_iface_t *iface;
01652 
01654   gz_stereo_data_t *data;
01655   
01656 } gz_stereo_t;
01657 
01658 
01660 extern gz_stereo_t *gz_stereo_alloc();
01661 
01663 extern void gz_stereo_free(gz_stereo_t *self);
01664 
01666 extern int gz_stereo_create(gz_stereo_t *self, gz_server_t *server, const char *id,
01667                             const char *model_type, int model_id, int parent_model_id);
01668 
01670 extern int gz_stereo_destroy(gz_stereo_t *self);
01671 
01673 extern int gz_stereo_open(gz_stereo_t *self, gz_client_t *client, const char *id);
01674 
01676 extern int gz_stereo_close(gz_stereo_t *self);
01677 
01680 extern int gz_stereo_lock(gz_stereo_t *self, int blocking);
01681 
01683 extern void gz_stereo_unlock(gz_stereo_t *self);
01684 
01686 extern int gz_stereo_post(gz_stereo_t *self);
01687 
01689 
01690 
01691 
01692 
01693 /***************************************************************************/
01696 
01705 
01706 typedef struct gz_truth_data
01707 {
01709   gz_data_t head;
01710 
01712   double time;
01713 
01715   double pos[3];
01716 
01718   double rot[4];
01719 
01721   int cmd_new;
01722   
01724   double cmd_pos[3];
01725 
01727   double cmd_rot[4];
01728    
01729 } gz_truth_data_t;
01730 
01731 
01733 typedef struct gz_truth
01734 {
01736   gz_iface_t *iface;
01737 
01739   gz_truth_data_t *data;
01740   
01741 } gz_truth_t;
01742 
01743 
01745 extern gz_truth_t *gz_truth_alloc();
01746 
01748 extern void gz_truth_free(gz_truth_t *self);
01749 
01751 extern int gz_truth_create(gz_truth_t *self, gz_server_t *server, const char *id,
01752                            const char *model_type, int model_id, int parent_model_id);
01753 
01755 extern int gz_truth_destroy(gz_truth_t *self);
01756 
01758 extern int gz_truth_open(gz_truth_t *self, gz_client_t *client, const char *id);
01759 
01761 extern int gz_truth_close(gz_truth_t *self);
01762 
01765 extern int gz_truth_lock(gz_truth_t *self, int blocking);
01766 
01768 extern void gz_truth_unlock(gz_truth_t *self);
01769 
01771 extern int gz_truth_post(gz_truth_t *self);
01772 
01774 extern void gz_truth_euler_from_quatern(gz_truth_t *self, double *e, double *q);
01775 
01777 extern void gz_truth_quatern_from_euler(gz_truth_t *self, double *q, double *e);
01778 
01780 
01781 
01782 
01783 /***************************************************************************/
01786 
01793 #define GAZEBO_WIFI_MAX_LINKS 16
01794 
01796 #define GAZEBO_WIFI_QUAL_DBM            1
01797 
01799 typedef struct gz_wifi_link
01800 {
01802   char ip[32];
01803 
01807   uint16_t qual, level, noise;
01808   
01809 } gz_wifi_link_t;
01810 
01811 
01812 typedef struct gz_wifi_data
01813 {
01815   gz_data_t head;
01816 
01818   double time;
01819 
01822   gz_wifi_link_t links[GAZEBO_WIFI_MAX_LINKS];
01823   uint16_t link_count;
01825 
01826 } gz_wifi_data_t;
01827 
01828 
01830 typedef struct gz_wifi
01831 {
01833   gz_iface_t *iface;
01834 
01836   gz_wifi_data_t *data;
01837   
01838 } gz_wifi_t;
01839 
01840 
01842 extern gz_wifi_t *gz_wifi_alloc();
01843 
01845 extern void gz_wifi_free(gz_wifi_t *self);
01846 
01848 extern int gz_wifi_create(gz_wifi_t *self, gz_server_t *server, const char *id,
01849                           const char *model_type, int model_id, int parent_model_id);
01850 
01852 extern int gz_wifi_destroy(gz_wifi_t *self);
01853 
01855 extern int gz_wifi_open(gz_wifi_t *self, gz_client_t *client, const char *id);
01856 
01858 extern int gz_wifi_close(gz_wifi_t *self);
01859 
01862 extern int gz_wifi_lock(gz_wifi_t *self, int blocking);
01863 
01865 extern void gz_wifi_unlock(gz_wifi_t *self);
01866 
01868 
01869 
01870 
01871 /***************************************************************************/
01874 
01883 #define GAZEBO_JOINT_MAX_JOINTS 20
01884 
01886 typedef struct gz_joint_data
01887 {
01889   int type;
01890  
01892   double anchor[3];
01893 
01895   double axis[3];
01896 
01898   double axis2[3];
01899 
01901   double angular_velocity;
01902 
01904   double angular_velocity2;
01905 
01907   double angle;
01908 
01910   double angle2;
01911 
01913   double cmd_angle;
01914 
01916   double cmd_angle2;
01917 
01918 } gz_joint_data_t;
01919 
01921 typedef struct gz_joints
01922 {
01924   gz_data_t head;
01925 
01927   double time;
01928 
01929   gz_joint_data_t joints[GAZEBO_JOINT_MAX_JOINTS];
01930 
01931   int joint_count;
01932 
01933 } gz_joints_t;
01934 
01935 
01937 typedef struct gz_joint
01938 {
01940   gz_iface_t *iface;
01941 
01943   gz_joints_t *data;
01944   
01945 } gz_joint_t;
01946 
01947 
01949 extern gz_joint_t *gz_joint_alloc();
01950 
01952 extern void gz_joint_free(gz_joint_t *self);
01953 
01955 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);
01956 
01958 extern int gz_joint_destroy(gz_joint_t *self);
01959 
01961 extern int gz_joint_open(gz_joint_t *self, gz_client_t *client, const char *id);
01962 
01964 extern int gz_joint_close(gz_joint_t *self);
01965 
01968 extern int gz_joint_lock(gz_joint_t *self, int blocking);
01969 
01971 extern void gz_joint_unlock(gz_joint_t *self);
01972 
01974 extern int gz_joint_post(gz_joint_t *self);
01975 
01977 
01978 
01979 
01980 
01981 
01982 #ifdef __cplusplus
01983 }
01984 #endif
01985 
01986 #endif

Last updated 12 September 2005 21:38:45