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 <string>
00032 #include <sys/types.h>
00033 #include <stdlib.h>
00034 #include <stdint.h>
00035 
00036 #include "IfaceFactory.hh"
00037 
00038 namespace gazebo
00039 {
00040 
00041 
00042 
00043 
00044 
00045 
00048 
00050 #define LIBGAZEBO_VERSION 0x070
00051 
00053 
00056 
00058 class Vec3
00059 {
00061   public: double x;
00062 
00064   public: double y;
00065 
00067   public: double z;
00068 };
00069 
00070 
00072 class Pose
00073 {
00075   public: Vec3 pos;
00076 
00078   public: double roll;
00079 
00081   public: double pitch;
00082 
00084   public: double yaw; 
00085 };
00086 
00088 class Color
00089 {
00091   public: float r;
00092 
00094   public: float g;
00095 
00097   public: float b;
00098 
00100   public: float a;
00101 };
00102 
00103 
00104 
00105 
00106 
00118 
00119 class Server
00120 {
00122   public: Server();
00123 
00125   public: virtual ~Server();
00126 
00128   public: void Init(int serverId, int force);
00129 
00131   public: void Fini();
00132 
00134   public: void Post();
00135 
00136   private: void SemInit(int force);
00137   private: void SemFini();
00138   private: void SemPost();
00139 
00141   public: int serverId;
00142 
00144   public: std::string filename;
00145 
00147   public: int semKey;
00148 
00150   public: int semId;
00151 };
00152 
00154 
00155 
00156   
00157 
00167 
00168 #define GZ_SEM_KEY 0x135135FA
00169   
00175 #define GZ_CLIENT_ID_USER_FIRST 0x00
00176 #define GZ_CLIENT_ID_USER_LAST  0x07
00177 #define GZ_CLIENT_ID_WXGAZEBO   0x08
00178 #define GZ_CLIENT_ID_PLAYER     0x09
00179 
00180   
00182 class Client 
00183 {
00185   public: Client();
00186 
00188   public: virtual ~Client();
00189 
00192   public: void Query(int server_id);
00193 
00196   public: void Connect(int server_id);
00197 
00201   public: void ConnectWait(int server_id, int client_id);
00202 
00204   public: void Disconnect();
00205 
00208   public: void Wait();
00209 
00210   private: void SemQuery(int server_id);
00211   private: void SemInit();
00212   private: void SemFini();
00213   private: void SemWait();
00214 
00216   public: int serverId;
00217 
00219   public: int clientId;
00220 
00222   public: std::string filename;
00223 
00225   public: int semKey;
00226 
00228   public: int semId;
00229 };
00230 
00233 
00243 
00244 #define GAZEBO_MAX_MODEL_TYPE 128
00245 
00247 class Iface
00248 {
00252   public: Iface(const std::string &type, size_t size);
00253 
00255   public: virtual ~Iface();
00256 
00260   public: virtual void Create(Server *server, std::string id);
00261 
00268   public: void Create(Server *server, std::string id,
00269                      const std::string &modelType, int modelId, 
00270                      int parentModelId);
00271 
00273   public: void Destroy();
00274 
00278   public: virtual void Open(Client *client, std::string id);
00279 
00281   public: virtual void Close();
00282 
00286   public: int Lock(int blocking);
00287 
00289   public: int Unlock();
00290 
00292   public: void Post();
00293 
00296   public: std::string GetType() const;
00297 
00298   private: std::string Filename(std::string id);
00299 
00301   public: Server *server;
00302   
00304   public: Client *client;
00305   
00307   public: int mmapFd;
00308 
00310   public: void *mMap;
00311 
00313   public: std::string filename;
00314 
00316   public: int version;
00317 
00319   public: size_t size;
00320 
00322   public: std::string modelType;
00323 
00325   public: int modelId;
00326 
00328   public: int parentModelId;
00329 
00331   protected: std::string type;
00332 
00334   private: int openCount;
00335 
00337   public: bool opened;
00338 };
00339 
00343 
00346 
00357 
00358 class SimulationData
00359 {
00361   public: double simTime;
00362 
00364   public: double pauseTime;
00365 
00367   public: double realTime;
00368 
00370   public: int pause;
00371 
00373   public: int reset;
00374 
00376   public: int save;
00377 
00379   public: uint8_t model_name[512];
00380 
00385   public: uint8_t model_req[32];
00386 
00389   public: Pose model_pose;
00390 };
00391 
00393 class SimulationIface : public Iface
00394 {
00396   public: SimulationIface(): Iface("simulation",sizeof(SimulationIface)+sizeof(SimulationData)) {}
00397 
00399   public: virtual ~SimulationIface() {this->data = NULL;}
00400 
00404   public: virtual void Create(Server *server, std::string id)
00405           {
00406             Iface::Create(server,id); 
00407             this->data = (SimulationData*)this->mMap; 
00408           }
00409 
00413   public: virtual void Open(Client *client, std::string id)
00414           {
00415             Iface::Open(client,id); 
00416             this->data = (SimulationData*)this->mMap; 
00417           }
00418 
00420   public: SimulationData *data;
00421 };
00422 
00424 
00425 
00426 
00427 
00430 
00444 
00445 #define GAZEBO_CAMERA_MAX_IMAGE_SIZE 640 * 480 * 3
00446 
00448 class CameraData
00449 {
00451   public: double time;
00452 
00454   public: unsigned int width;
00455 
00457   public: unsigned int height;
00458 
00460   public: unsigned int image_size;
00461 
00463   public: unsigned char image[GAZEBO_CAMERA_MAX_IMAGE_SIZE];
00464   
00465 };
00466 
00468 class CameraIface : public Iface
00469 {
00471   public: CameraIface():Iface("camera", sizeof(CameraIface)+sizeof(CameraData)) {}
00472 
00474   public: virtual ~CameraIface() {this->data = NULL;}
00475 
00479   public: virtual void Create(Server *server, std::string id)
00480           {
00481             Iface::Create(server,id); 
00482             this->data = (CameraData*)this->mMap; 
00483           }
00484 
00488   public: virtual void Open(Client *client, std::string id)
00489           {
00490             Iface::Open(client,id); 
00491             this->data = (CameraData*)this->mMap; 
00492           }
00493 
00495   public: CameraData *data;
00496 };
00497 
00498 
00500 
00501 
00502 
00503 
00506 
00518 
00519 class PositionData
00520 {
00522   public: double time;
00523 
00525   public: Pose pose;
00526 
00528   public: Pose velocity;
00529 
00531   public: int stall;
00532 
00534   public: int cmdEnableMotors;
00535   
00537   public: Pose cmdVelocity;
00538 
00540   public: bool opened;
00541 };
00542 
00544 class PositionIface : public Iface
00545 {
00547   public: PositionIface():Iface("position", sizeof(PositionIface)+sizeof(PositionData)) {}
00548 
00550   public: virtual ~PositionIface() {this->data = NULL;}
00551 
00555   public: virtual void Create(Server *server, std::string id)
00556           {
00557             Iface::Create(server,id); 
00558             this->data = (PositionData*)this->mMap; 
00559             this->data->opened = false;
00560           }
00561 
00565   public: virtual void Open(Client *client, std::string id)
00566           {
00567             Iface::Open(client,id); 
00568             this->data = (PositionData*)this->mMap; 
00569             this->data->opened = true;
00570           }
00571 
00573   public: virtual void Close()
00574           {
00575             this->data->opened = false;
00576             Iface::Close();
00577           }
00578 
00579 
00581   public: PositionData *data;
00582 };
00583 
00585 
00586 
00587 
00590 
00601 
00602 #define GAZEBO_GRAPHICS3D_MAX_POINTS 1024
00603 
00605 class Graphics3dData
00606 {
00608   enum DrawMode {POINTS, LINES, LINE_STRIP, LINE_LOOP, TRIANGLES, TRIANGLE_STRIP, TRIANGLE_FAN, QUADS, QUAD_STRIP, POLYGON};
00609 
00611   public: DrawMode drawmode;
00612 
00614   public: unsigned int point_count; 
00615 
00617   public: Vec3 points[GAZEBO_GRAPHICS3D_MAX_POINTS];
00618 
00620   public: Color color;
00621 };
00622 
00624 class Graphics3dIface : public Iface
00625 {
00626 
00628   public: Graphics3dIface():Iface("graphics3d", sizeof(Graphics3dIface)+sizeof(Graphics3dData)) {}
00629 
00631   public: virtual ~Graphics3dIface() {this->data = NULL;}
00632 
00636   public: virtual void Create(Server *server, std::string id)
00637           {
00638             Iface::Create(server,id); 
00639             this->data = (Graphics3dData*)this->mMap; 
00640           }
00641 
00645   public: virtual void Open(Client *client, std::string id)
00646           {
00647             Iface::Open(client,id); 
00648             this->data = (Graphics3dData*)this->mMap; 
00649           }
00650 
00652   public: Graphics3dData *data;
00653 };
00654 
00655 
00657 
00658 
00659 
00660   
00661 
00664 
00676 
00677 #define GZ_LASER_MAX_RANGES 1024
00678 
00680 class LaserData
00681 {
00683   public: bool opened;
00684 
00686   public: double time;
00687   
00689   public: double min_angle;
00690 
00692   public: double max_angle;
00693 
00695   public: double res_angle;
00696 
00698   public: double max_range;
00699 
00701   public: int range_count;
00702   
00704   public: double ranges[GZ_LASER_MAX_RANGES];
00705 
00707   public: int intensity[GZ_LASER_MAX_RANGES];
00708   
00710   public: int cmd_new_angle;
00711 
00713   public: int cmd_new_length;
00714 
00716   public: double cmd_max_range;
00717 
00719   public: double cmd_min_angle;
00720 
00722   public: double cmd_max_angle;
00723 
00725   public: int cmd_range_count;
00726 };
00727 
00729 class LaserIface : public Iface
00730 {
00732   public: LaserIface():Iface("laser", sizeof(LaserIface)+sizeof(LaserData)) {}
00733 
00735   public: virtual ~LaserIface() {this->data = NULL;}
00736 
00740   public: virtual void Create(Server *server, std::string id)
00741           {
00742             Iface::Create(server,id); 
00743             this->data = (LaserData*)this->mMap; 
00744             this->data->opened=false;
00745           }
00746 
00750   public: virtual void Open(Client *client, std::string id)
00751           {
00752             Iface::Open(client,id); 
00753             this->data = (LaserData*)this->mMap; 
00754             this->data->opened = true;
00755           }
00756 
00758   public: virtual void Close()
00759           {
00760             this->data->opened = false;
00761             Iface::Close();
00762           }
00763 
00765   public: LaserData *data;
00766 };
00767 
00769 
00770 
00771 
00772 
00775 
00787 
00788 #define GZ_FIDUCIAL_MAX_FIDS 401
00789 
00791 class FiducialFid
00792 {
00794   public: int id;
00795 
00797   public: Pose pose;
00798 };
00799 
00801 class FiducialData
00802 {
00804   public: double time;
00805 
00807   public: int count;
00808 
00810   public: FiducialFid fids[GZ_FIDUCIAL_MAX_FIDS];
00811 };
00812 
00814 class FiducialIface : public Iface
00815 {
00817   public: FiducialIface():Iface("fiducial", sizeof(FiducialIface)+sizeof(FiducialData)) {}
00818 
00820   public: virtual ~FiducialIface() {this->data = NULL;}
00821 
00823   public: virtual void Create(Server *server, std::string id)
00824           {
00825             Iface::Create(server,id); 
00826             this->data = (FiducialData*)this->mMap; 
00827           }
00828 
00830   public: virtual void Open(Client *client, std::string id)
00831           {
00832             Iface::Open(client,id); 
00833             this->data = (FiducialData*)this->mMap; 
00834           }
00835 
00837   public: FiducialData *data;
00838 };
00839 
00841 
00842 
00843 
00846 
00856 
00857 class FactoryData
00858 {
00860   public: double time;
00861 
00863   public: uint8_t newModel[4096];
00864 
00866   public: uint8_t deleteModel[512];
00867 };
00868 
00870 class FactoryIface : public Iface
00871 {
00873   public: FactoryIface():Iface("factory", sizeof(FactoryIface)+sizeof(FactoryData)) {}
00874 
00876   public: virtual ~FactoryIface() {this->data = NULL;}
00877 
00879   public: virtual void Create(Server *server, std::string id)
00880           {
00881             Iface::Create(server,id); 
00882             this->data = (FactoryData*)this->mMap; 
00883           }
00884 
00886   public: virtual void Open(Client *client, std::string id)
00887           {
00888             Iface::Open(client,id); 
00889             this->data = (FactoryData*)this->mMap; 
00890           }
00891 
00893   public: FactoryData *data;
00894 };
00895 
00897 
00898 
00899 
00902 
00914 #define GAZEBO_GRIPPER_STATE_OPEN 1
00915 
00916 #define GAZEBO_GRIPPER_STATE_CLOSED 2
00917 
00918 #define GAZEBO_GRIPPER_STATE_MOVING 3
00919 
00920 #define GAZEBO_GRIPPER_STATE_ERROR 4
00921 
00923 #define GAZEBO_GRIPPER_CMD_OPEN 1
00924 
00925 #define GAZEBO_GRIPPER_CMD_CLOSE 2
00926 
00927 #define GAZEBO_GRIPPER_CMD_STOP 3
00928 
00929 #define GAZEBO_GRIPPER_CMD_STORE 4
00930 
00931 #define GAZEBO_GRIPPER_CMD_RETRIEVE 5
00932 
00933 
00935 class GripperData
00936 {
00938   public: double time;
00939 
00941   public: int cmd;
00942 
00944   public: int state;
00945 
00947   public: int grip_limit_reach;
00948 
00950   public: int lift_limit_reach;
00951 
00953   public: int outer_beam_obstruct;
00954 
00956   public: int inner_beam_obstruct;
00957 
00959   public: int left_paddle_open;
00960 
00962   public: int right_paddle_open;
00963 
00965   public: int lift_up;
00966 
00968   public: int lift_down;
00969 };
00970 
00972 class GripperIface : public Iface
00973 {
00975   public: GripperIface():Iface("gripper", sizeof(GripperIface)+sizeof(GripperData)) {}
00976 
00978   public: virtual ~GripperIface() {this->data = NULL;}
00979 
00981   public: virtual void Create(Server *server, std::string id)
00982           {
00983             Iface::Create(server,id); 
00984             this->data = (GripperData*)this->mMap; 
00985           }
00986 
00988   public: virtual void Open(Client *client, std::string id)
00989           {
00990             Iface::Open(client,id); 
00991             this->data = (GripperData*)this->mMap; 
00992           }
00993 
00995   public: GripperData *data;
00996 };
00997 
00999 
01000 
01001 
01002 
01005 
01014 
01015 #define GAZEBO_ACTARRAY_MAX_NUM_ACTUATORS 16
01016 
01017 
01019 #define GAZEBO_ACTARRAY_ACTSTATE_IDLE     1
01020 
01022 #define GAZEBO_ACTARRAY_ACTSTATE_MOVING   2
01023 
01025 #define GAZEBO_ACTARRAY_ACTSTATE_BRAKED   3
01026 
01028 #define GAZEBO_ACTARRAY_ACTSTATE_STALLED  4
01029 
01031 #define GAZEBO_ACTARRAY_TYPE_LINEAR       1
01033 #define GAZEBO_ACTARRAY_TYPE_ROTARY       2
01034 
01036 #define GAZEBO_ACTARRAY_POWER_REQ         1
01038 #define GAZEBO_ACTARRAY_BRAKES_REQ        2
01040 #define GAZEBO_ACTARRAY_GET_GEOM_REQ      3
01042 #define GAZEBO_ACTARRAY_SPEED_REQ         4
01043 
01045 #define GAZEBO_ACTARRAY_POS_CMD           1
01047 #define GAZEBO_ACTARRAY_SPEED_CMD         2
01049 #define GAZEBO_ACTARRAY_HOME_CMD          3
01050 
01051 
01053 class ActarrayActuatorGeom
01054 {
01055 
01057 #define GAZEBO_ACTARRAY_DATA_STATE        1
01058 
01059 
01061   public: uint8_t type;
01062 
01064   public: float min;
01065 
01067   public: float center;
01068 
01070   public: float max;
01071 
01073   public: float home;
01074 
01076   public: float config_speed;
01077 
01079   public: float max_speed;
01080 
01082   public: uint8_t hasbrakes;
01083 };
01084 
01086 class ActarrayActuator
01087 {
01089   public: float position;
01091   public: float speed;
01093   public: uint8_t state;
01094 
01095 }; 
01096 
01098 class ActarrayData
01099 {
01101   public: unsigned int actuators_count;
01102   
01104   public: double time;
01105   
01107   public: ActarrayActuator actuators[GAZEBO_ACTARRAY_MAX_NUM_ACTUATORS];
01108   
01110   public: ActarrayActuatorGeom actuator_geoms[GAZEBO_ACTARRAY_MAX_NUM_ACTUATORS];
01111   
01113   public: float cmd_pos[GAZEBO_ACTARRAY_MAX_NUM_ACTUATORS];
01114   
01116   public: float cmd_speed[GAZEBO_ACTARRAY_MAX_NUM_ACTUATORS];
01117   
01119   public: int bad_cmd;
01120   
01122   public: unsigned int joint_mode[GAZEBO_ACTARRAY_MAX_NUM_ACTUATORS];
01123   
01124 };
01125 
01127 class ActarrayIface : public Iface
01128 {
01130   public: ActarrayIface():Iface("actarray", sizeof(ActarrayIface)+sizeof(ActarrayData)) {}
01131 
01133   public: virtual ~ActarrayIface() {this->data = NULL;}
01134 
01138   public: virtual void Create(Server *server, std::string id)
01139           {
01140            Iface::Create(server,id); 
01141            this->data = (ActarrayData*)this->mMap; 
01142           }
01143 
01147   public: virtual void Open(Client *client, std::string id)
01148           {
01149             Iface::Open(client,id); 
01150             this->data = (ActarrayData*)this->mMap; 
01151           }
01152 
01154   public: ActarrayData *data;
01155 };
01156 
01158 
01159 
01160 }
01161 
01162 #endif