Gazebo

libgazebo


Detailed Description

A shared memory interface to Gazebo.


Modules

 Interfaces
 Interfaces to libgazebo.

Classes

class  Vec3
 Vector 3 class. More...
class  Pose
 Pose class. More...
class  Color
 Color class. More...
class  Server
 Server class. More...
class  Client
 Client class. More...
class  Iface
 Base class for all interfaces. More...
class  GazeboData
#define GZ_SEM_KEY   0x135135FA
 Semaphore key used by Gazebo.
#define GZ_CLIENT_ID_USER_FIRST   0x00
 Reserved client IDs.
#define GZ_CLIENT_ID_USER_LAST   0x07
 Semaphore key used by Gazebo.
#define GZ_CLIENT_ID_WXGAZEBO   0x08
 Semaphore key used by Gazebo.
#define GZ_CLIENT_ID_PLAYER   0x09
 Semaphore key used by Gazebo.
#define GAZEBO_MAX_MODEL_TYPE   128
 Max length of model type string.

Defines

#define LIBGAZEBO_VERSION   0x070
 Interface version number.

Functions

virtual ~Server ()
 Destructor.
void Init (int serverId, int force)
 Initialize the server.
void Fini ()
 Finalize the server.
void Post ()
 Tell clients that new data is available.
virtual ~Client ()
 Destroy a client.
void Query (int server_id)
 Test for the presence of the server.
void Connect (int server_id)
 Connect to the server (non-blocking mode).
void ConnectWait (int server_id, int client_id)
 Connect to the server (blocking mode).
void Disconnect ()
 Disconnect from the server.
void Wait ()
 Wait for new data to be posted (blocking mode).
virtual ~Iface ()
 Destroy an interface.
virtual void Create (Server *server, std::string id)
 Create the interface (used by Gazebo server).
void Create (Server *server, std::string id, const std::string &modelType, int modelId, int parentModelId)
 Create the interface (used by Gazebo server).
void Destroy ()
 Destroy the interface (server).
virtual void Open (Client *client, std::string id)
 Open an existing interface.
virtual void Close ()
 Close the interface.
int Lock (int blocking)
 Lock the interface.
int Unlock ()
 Unlock the interface.
void Post ()
 Tell clients that new data is available.
int GetOpenCount ()
 Get the number of connections.
std::string GetType () const
 Get the iface type.
virtual ~SimulationIface ()
 Destroy an interface.
virtual void Create (Server *server, std::string id)
 Create a simulation interface server Pointer to the server id String id.
virtual void Open (Client *client, std::string id)
 Open a simulation interface.
virtual ~AudioIface ()
 Destructor.
virtual void Create (Server *server, std::string id)
 Create the interface (used by Gazebo server).
virtual void Open (Client *client, std::string id)
 Open an existing interface.
virtual ~CameraIface ()
 Destructor.
virtual void Create (Server *server, std::string id)
 Create the interface (used by Gazebo server).
virtual void Open (Client *client, std::string id)
 Open an existing interface.
virtual ~PositionIface ()
 Destructor.
virtual void Create (Server *server, std::string id)
 Create the interface (used by Gazebo server).
virtual void Open (Client *client, std::string id)
 Open an existing interface.
virtual ~Graphics3dIface ()
 Destructor.
virtual void Create (Server *server, std::string id)
 Create the interface (used by Gazebo server).
virtual void Open (Client *client, std::string id)
 Open an existing interface.
virtual ~LaserIface ()
 Destructor.
virtual void Create (Server *server, std::string id)
 Create the interface (used by Gazebo server).
virtual void Open (Client *client, std::string id)
 Open an existing interface.
virtual ~FiducialIface ()
 Destructor.
virtual void Create (Server *server, std::string id)
 Create the server.
virtual void Open (Client *client, std::string id)
 Open the iface.
virtual ~FactoryIface ()
 Destructor.
virtual void Create (Server *server, std::string id)
 Create the server.
virtual void Open (Client *client, std::string id)
 Open the iface.
virtual ~GripperIface ()
 Destructor.
virtual void Create (Server *server, std::string id)
 Create the server.
virtual void Open (Client *client, std::string id)
 Open the iface.
virtual ~ActarrayIface ()
 Destroy and Interface.
virtual void Create (Server *server, std::string id)
 Create the interface (used by Gazebo server).
virtual void Open (Client *client, std::string id)
 Open an existing interface.
virtual ~PTZIface ()
 Destructor.
virtual void Create (Server *server, std::string id)
 Create the server.
virtual void Open (Client *client, std::string id)
 Open the iface.
virtual ~StereoCameraIface ()
 Destructor.
virtual void Create (Server *server, std::string id)
 Create the server.
virtual void Open (Client *client, std::string id)
 Open the iface.

Variables

double y
 Y value.
double z
 Z value.
double roll
 Rotation information. Roll Euler angle.
double pitch
 Rotation information. Pitch Euler angle.
double yaw
 Rotation information. Yaw Euler angle.
float g
 Green color information.
float b
 Blue color information.
float a
 Alpha color information.
int serverId
 The server id.
std::string filename
 The directory containing mmap files.
int semKey
 The semphore key.
int semId
 The semphore id.
int serverId
 The server id.
int clientId
 The client id.
std::string filename
 The directory containing mmap files.
int semKey
 The semphore key.
int semId
 The semphore id.
Server * server
 The server we are associated with.
Client * client
 The client we are associated with.
int mmapFd
 File descriptor for the mmap file.
void * mMap
 Pointer to the mmap'ed mem.
std::string filename
 The name of the file we created/opened.
std::string type
 type of interface
double time
int version
size_t size
int modelId
 ID of the model that owns this interface.
int parentModelId
 ID of the parent model.
std::string modelType
 Type of model that owns this interface.
double simTime
 Elapsed simulation time.
double pauseTime
 Accumpated pause time (this interface may be updated with the server is paused).
double realTime
 Elapsed real time since start of simulation (from system clock).
int state
 state of the simulation : 0 paused, 1 running -1 not_started/exiting
bool pause
 Pause simulation (set by client) should check the state Changes the state of the simulation from pause to play and viceversa.
int reset
 Reset simulation (set by client).
int save
 Save current poses to world file (set by client).
char model_name [512]
 Name of the model to get/set data.
char model_req [32]
 Type of request
  • "get_pose" Sets model_pose to the pose of model_name
  • "set_pose3d" Set the model_name to model_pose
  • "set_pose2d" Set the model_name to model_pose.

Pose model_pose
 Pose of the model.
SimulationData * data
 Pointer to the simulation data.
double time
 Data timestamp.
bool loop
 Play in a loop?
float gain
 Gain.
bool stream
 streaming of the file?
int cmd_play
 Play.
int cmd_pause
 Pause.
int cmd_stop
 Stop.
int cmd_reset
 Reset to the beginning.
int state
 state given by the server, 1 for playing.
char url [256]
 location of the file
Pose audio_pose
 3D Pose of the audio, given by the server
AudioData * data
 Pointer to the audio data.
unsigned int width
 Width of image in pixels.
unsigned int height
 Height of image in pixels.
unsigned int image_size
 Size of the image in bytes.
unsigned char image [640 *480 *3]
 Image pixel data.
double hfov
 Horizontal field of view of the camera in radians.
Pose camera_pose
 Pose of the camera.
CameraData * data
 Pointer to the camera data.
Pose pose
 Pose (usually global cs).
Pose velocity
 Velocity.
int stall
 Motor stall flag.
int cmdEnableMotors
 Enable the motors.
Pose cmdVelocity
 Commanded robot velocities (robot cs).
PositionData * data
 Pointer to the position data.
DrawMode drawmode
 Drawing mode.
unsigned int point_count
 Number of vertices.
Vec3 points [1024]
 Vertices.
Color color
 Drawing color.
Graphics3dData * data
 Pointer to the graphics3d data.
double min_angle
 Range scan min angle.
double max_angle
 Range scan max angle.
double res_angle
 Angular resolution.
double max_range
 Max range value.
int range_count
 Number of range readings.
double ranges [1024]
 Range readings.
int intensity [1024]
 Intensity readings.
int cmd_new_angle
 New command ( 0 or 1 ).
int cmd_new_length
 New command ( 0 or 1 ).
double cmd_max_range
 Commanded range value.
double cmd_min_angle
 Commaned min angle.
double cmd_max_angle
 Commaned max angle.
int cmd_range_count
 Commaned range count.
LaserData * data
 Pointer to the laser data.
Pose pose
 Fiducial pose.
int count
 Number of fiducials.
FiducialFid fids [401]
 Observed fiducials.
FiducialData * data
 Pointer to the fiducial data.
uint8_t newModel [4096]
 String describing the model to be initiated.
uint8_t deleteModel [512]
 Delete a model by name.
FactoryData * data
 Pointer to the factory data.
int cmd
 Current command for the gripper.
int state
 Current state of the gripper.
int grip_limit_reach
 Gripped limit reached flag.
int lift_limit_reach
 Lift limit reached flag.
int outer_beam_obstruct
 Outer beam obstruct flag.
int inner_beam_obstruct
 Inner beam obstructed flag.
int left_paddle_open
 Left paddle open flag.
int right_paddle_open
 Right paddle open flag.
int lift_up
 Lift up flag.
int lift_down
 Lift down flag.
GripperData * data
 Pointer to the gripper data.
uint8_t type
 The type of the actuator - linear or rotary.
float min
 Min range of motion (m or rad depending on the type).
float center
 Center position (m or rad).
float max
 Max range of motion (m or rad depending on the type).
float home
 Home position (m or rad depending on the type).
float config_speed
 The configured speed - different from current speed.
float max_speed
 The maximum achievable speed of the actuator.
uint8_t hasbrakes
 If the actuator has brakes or not.
float speed
 The speed of the actuator in m/s or rad/s depending on the type.
uint8_t state
 The current state of the actuator.
unsigned int actuators_count
 The number of actuators in the array.
ActarrayActuator actuators [16]
 The actuator data.
ActarrayActuatorGeom actuator_geoms [16]
 The actuators geoms.
float cmd_pos [16]
 position commands
float cmd_speed [16]
 speed commands
int bad_cmd
 bad command flag - (speed to high set for the actuators or position not reachable)
bool new_cmd
 True if new command.
unsigned int joint_mode [16]
 position / speed comand
ActarrayData * data
 Pointer to the act array data.
double pan
 Measured pan angle (radians).
double tilt
 Measured tilt angle (radians).
double zoom
 Measured field of view (radians).
double cmd_pan
 Commanded pan angle (radians).
double cmd_tilt
 Commanded tilt angle (radians).
double cmd_zoom
 Commanded field of view (radians).
PTZData * data
 Pointer to the ptz data.
unsigned int width
 Width of image in pixels.
unsigned int height
 Height of image in pixels.
float farClip
 Far clip distance in meters.
float nearClip
 Near clip distance in meters.
unsigned int left_rgb_size
 Left image size.
unsigned char left_rgb [640 *480 *3]
 left image (R8G8B8)
unsigned int right_rgb_size
 Right image size.
unsigned char right_rgb [640 *480 *3]
 Right image (R8G8B8).
unsigned int left_disparity_size
 Left disparity size.
float left_disparity [640 *480]
 Left disparity (float).
unsigned int right_disparity_size
 Right Disparity size.
float right_disparity [640 *480]
 Right disparity (float).
StereoCameraData * data
 Pointer to the stereo data.


Define Documentation

#define GAZEBO_MAX_MODEL_TYPE   128

Max length of model type string.

For internal use only.

#define GZ_CLIENT_ID_PLAYER   0x09

Semaphore key used by Gazebo.

The client object is used by Gazebo clients to establish a connection with a running server.

#define GZ_CLIENT_ID_USER_FIRST   0x00

Reserved client IDs.

User programs may use numbers in the range GZ_SEM_NUM_USER to GZ_SEM_NUM_USER_LAST, inclusive. All other semaphore numbers are reserved.

#define GZ_CLIENT_ID_USER_LAST   0x07

Semaphore key used by Gazebo.

The client object is used by Gazebo clients to establish a connection with a running server.

#define GZ_CLIENT_ID_WXGAZEBO   0x08

Semaphore key used by Gazebo.

The client object is used by Gazebo clients to establish a connection with a running server.

#define GZ_SEM_KEY   0x135135FA

Semaphore key used by Gazebo.

The client object is used by Gazebo clients to establish a connection with a running server.


Function Documentation

void Connect ( int  server_id  )  [inherited]

Connect to the server (non-blocking mode).

Parameters:
server_id Id of the server

void ConnectWait ( int  server_id,
int  client_id 
) [inherited]

Connect to the server (blocking mode).

Parameters:
server_id Server ID; each server must have a unique id.
client_id Client ID; in blocking mode, each client must have a unique id.

virtual void Create ( Server server,
std::string  id 
) [inline, virtual, inherited]

Create the interface (used by Gazebo server).

Parameters:
server Pointer to the server
id Id of the interface

Reimplemented from Iface.

virtual void Create ( Server server,
std::string  id 
) [inline, virtual, inherited]

Create the interface (used by Gazebo server).

Parameters:
server Pointer to the server
id Id of the interface

Reimplemented from Iface.

virtual void Create ( Server server,
std::string  id 
) [inline, virtual, inherited]

Create the interface (used by Gazebo server).

Parameters:
server Pointer to the server
id Id of the interface

Reimplemented from Iface.

virtual void Create ( Server server,
std::string  id 
) [inline, virtual, inherited]

Create the interface (used by Gazebo server).

Parameters:
server Pointer to the server
id Id of the interface

Reimplemented from Iface.

virtual void Create ( Server server,
std::string  id 
) [inline, virtual, inherited]

Create the interface (used by Gazebo server).

Parameters:
server Pointer to the server
id Id of the interface

Reimplemented from Iface.

virtual void Create ( Server server,
std::string  id 
) [inline, virtual, inherited]

Create the interface (used by Gazebo server).

Parameters:
server Pointer to the server
id Id of the interface

Reimplemented from Iface.

void Create ( Server server,
std::string  id,
const std::string &  modelType,
int  modelId,
int  parentModelId 
) [inherited]

Create the interface (used by Gazebo server).

Parameters:
server Pointer to the server
id Id of the server
modelType Type of the model
modelId Id of the model
parentModelId Id of the model's parent

virtual void Create ( Server server,
std::string  id 
) [virtual, inherited]

Create the interface (used by Gazebo server).

Parameters:
server Pointer to the server
id Id of the interface

Reimplemented in SimulationIface, AudioIface, CameraIface, PositionIface, Graphics3dIface, LaserIface, FiducialIface, FactoryIface, GripperIface, ActarrayIface, PTZIface, and StereoCameraIface.

std::string GetType (  )  const [inherited]

Get the iface type.

Returns:
The type of interface

int Lock ( int  blocking  )  [inherited]

Lock the interface.

Parameters:
blocking 1=caller should block, 0=no-block
Returns:
0 if the lock is acquired

virtual void Open ( Client client,
std::string  id 
) [inline, virtual, inherited]

Open an existing interface.

Parameters:
client Pointer to the client
id Id of the interface

Reimplemented from Iface.

virtual void Open ( Client client,
std::string  id 
) [inline, virtual, inherited]

Open an existing interface.

Parameters:
client Pointer to the client
id Id of the interface

Reimplemented from Iface.

virtual void Open ( Client client,
std::string  id 
) [inline, virtual, inherited]

Open an existing interface.

Parameters:
client Pointer to the client
id Id of the interface

Reimplemented from Iface.

virtual void Open ( Client client,
std::string  id 
) [inline, virtual, inherited]

Open an existing interface.

Parameters:
client Pointer to the client
id Id of the interface

Reimplemented from Iface.

virtual void Open ( Client client,
std::string  id 
) [inline, virtual, inherited]

Open an existing interface.

Parameters:
client Pointer to the client
id Id of the interface

Reimplemented from Iface.

virtual void Open ( Client client,
std::string  id 
) [inline, virtual, inherited]

Open an existing interface.

Parameters:
client Pointer to the client
id Id of the interface

Reimplemented from Iface.

virtual void Open ( Client client,
std::string  id 
) [inline, virtual, inherited]

Open a simulation interface.

Parameters:
client Pointer to the client
id String name of the client

Reimplemented from Iface.

virtual void Open ( Client client,
std::string  id 
) [virtual, inherited]

Open an existing interface.

Parameters:
client Pointer to the client
id Id of the interface

Reimplemented in SimulationIface, AudioIface, CameraIface, PositionIface, Graphics3dIface, LaserIface, FiducialIface, FactoryIface, GripperIface, ActarrayIface, PTZIface, and StereoCameraIface.

void Query ( int  server_id  )  [inherited]

Test for the presence of the server.

Parameters:
server_id Id of the server


Variable Documentation

Pose model_pose [inherited]

Pose of the model.

See also:
model_req


Last updated Aug 04 2007