next up previous contents
Next: A. Platform Specific Build Up: 2 Developer Guide Previous: 9. libgazebo    Contents

Subsections


10. libgazebo Interface Reference

libgazebo currently supports the following interfaces:

A detailed reference for each of these interfaces is included in the following sections.

10.1 camera

The camera interface allows clients to read images from a simulated camera. This interface gives the view of the world as the camera onboard a robotic platform would see it. This can be fed to image processing algorithms such as the CMVision blobfinder to recover blobs. Useful for testing visual-servoing type stuff.

// Camera interface
typedef struct _gz_camera_data_t
{
  // Common data structure
  gz_data_t head;
  
  // Data timestamp
  double time;

  // Image dimensions
  unsigned int width, height;

  // Image depth (bits: 8, 16, 24 or 32)
  int depth;

  // Image pixel data
  unsigned int image_size;
  unsigned char image[GAZEBO_MAX_IMAGE_SIZE];
  
} gz_camera_data_t;

// The camera interface
typedef struct _gz_camera_t
{
  // General interface info
  gz_iface_t *iface;

  // Pointer to interface data area
  gz_camera_data_t *data;
  
} gz_camera_t;

// Create an interface
extern gz_camera_t *gz_camera_alloc();

// Destroy an interface
extern void gz_camera_free(gz_camera_t *self);

// Create the interface (used by Gazebo server)
extern int gz_camera_create(gz_camera_t *self, gz_server_t *server, const char *id);

// Destroy the interface (server)
extern int gz_camera_destroy(gz_camera_t *self);

// Open an existing interface (used by Gazebo clients)
extern int gz_camera_open(gz_camera_t *self, gz_client_t *client, const char *id);

// Close the interface (client)
extern int gz_camera_close(gz_camera_t *self);

// Lock the interface.  Set blocking to 1 if the caller should block
// until the lock is acquired.  Returns 0 if the lock is acquired.
extern int gz_camera_lock(gz_camera_t *self, int blocking);

// Unlock the interface
extern void gz_camera_unlock(gz_camera_t *self);

10.2 factory

The factory interface allows clients to send XML strings to a factory in order to dynamically create models.

// Factory interface
typedef struct _gz_factory_data_t
{
  // Common data structures
  gz_data_t head;

  // Data timestamp
  double time;

  // String describing the model to be instantiated
  uint8_t string[4096];
  
} gz_factory_data_t;

// The position interface
typedef struct _gz_factory_t
{
  // General interface info
  gz_iface_t *iface;

  // Pointer to interface data area
  gz_factory_data_t *data;
  
} gz_factory_t;

// Create an interface
extern gz_factory_t *gz_factory_alloc();

// Destroy an interface
extern void gz_factory_free(gz_factory_t *self);

// Create the interface (used by Gazebo server)
extern int gz_factory_create(gz_factory_t *self, gz_server_t *server, const char *id);

// Destroy the interface (server)
extern int gz_factory_destroy(gz_factory_t *self);

// Open an existing interface (used by Gazebo clients)
extern int gz_factory_open(gz_factory_t *self, gz_client_t *client, const char *id);

// Close the interface (client)
extern int gz_factory_close(gz_factory_t *self);

// Lock the interface.  Set blocking to 1 if the caller should block
// until the lock is acquired.  Returns 0 if the lock is acquired.
extern int gz_factory_lock(gz_factory_t *self, int blocking);

// Unlock the interface
extern void gz_factory_unlock(gz_factory_t *self);

10.3 fiducial

The fiducial interface allows clients to determine the identity, range, bearing and orientation (relative to some sensor) of objects in the world. For example, this interface is used by the SickLMS200 model to return data from simulated retro-reflective barcodes.

// Data for a single fiducial
typedef struct _gz_fiducial_fid_t
{
  // Fiducial id
  int id;

  // Fiducial range, bearing and orientation
  double pose[3];
  
} gz_fiducial_fid_t;

// Fiducial data
typedef struct _gz_fiducial_data_t
{
  // Common data structures
  gz_data_t head;

  // Data timestamp
  double time;
  
  // Observed fiducials
  int fid_count;
  gz_fiducial_fid_t fids[GZ_FIDUCIAL_MAX_FIDS];
  
} gz_fiducial_data_t;

// The fiducial interface
typedef struct _gz_fiducial_t
{
  // General interface info
  gz_iface_t *iface;

  // Pointer to interface data area
  gz_fiducial_data_t *data;
  
} gz_fiducial_t;

// Create an interface
extern gz_fiducial_t *gz_fiducial_alloc();

// Destroy an interface
extern void gz_fiducial_free(gz_fiducial_t *self);

// Create the interface (used by Gazebo server)
extern int gz_fiducial_create(gz_fiducial_t *self, gz_server_t *server, const char *id);

// Destroy the interface (server)
extern int gz_fiducial_destroy(gz_fiducial_t *self);

// Open an existing interface (used by Gazebo clients)
extern int gz_fiducial_open(gz_fiducial_t *self, gz_client_t *client, const char *id);

// Close the interface (client)
extern int gz_fiducial_close(gz_fiducial_t *self);

// Lock the interface.  Set blocking to 1 if the caller should block
// until the lock is acquired.  Returns 0 if the lock is acquired.
extern int gz_fiducial_lock(gz_fiducial_t *self, int blocking);

// Unlock the interface
extern void gz_fiducial_unlock(gz_fiducial_t *self);

10.4 gps

The gps interface allows the user to receive GPS (Latitude/Longitude/Altitude) information for the robot platform on which the GPS device is mounted.

// GPS interface
typedef struct _gz_gps_data_t
{
  // Common data structure
  gz_data_t head;
  
  // Data timestamp
  double time;

  // Latitude and longitude, in degrees.
  double latitude;
  double longitude;

  // Altitude, in meters.
  double altitude;

  // UTM coordinates (meters)
  double utm_e, utm_n;

  // Number of satellites in view.
  int satellites;

  // Fix quality
  int quality;
    
  // Horizontal dilution of position (HDOP)
  double hdop;

  // Errors
  double err_horz, err_vert;

  // ?
  double origin_longitude, origin_latitude, origin_altitude;
  
} gz_gps_data_t;

// The GPS interface
typedef struct _gz_gps_t
{
  // General interface info
  gz_iface_t *iface;

  // Pointer to interface data area
  gz_gps_data_t *data;
  
} gz_gps_t;

// Create an interface
extern gz_gps_t *gz_gps_alloc();

// Destroy an interface
extern void gz_gps_free(gz_gps_t *self);

// Create the interface (used by Gazebo server)
extern int gz_gps_create(gz_gps_t *self, gz_server_t *server, const char *id);

// Destroy the interface (server)
extern int gz_gps_destroy(gz_gps_t *self);

// Open an existing interface (used by Gazebo clients)
extern int gz_gps_open(gz_gps_t *self, gz_client_t *client, const char *id);

// Close the interface (client)
extern int gz_gps_close(gz_gps_t *self);

// Lock the interface.  Set blocking to 1 if the caller should block
// until the lock is acquired.  Returns 0 if the lock is acquired.
extern int gz_gps_lock(gz_gps_t *self, int blocking);

// Unlock the interface
extern void gz_gps_unlock(gz_gps_t *self);

10.5 laser

The laser interface allows clients to read data from a simulated laser range finder (such as the SICK LMS200). Some configuration of this device is also allowed.

// Laser data
typedef struct _gz_laser_data_t
{
  // Common data structures
  gz_data_t head;

  // Data timestamp
  double time;
  
  // Range scan angles
  double min_angle, max_angle;

  // Angular resolution
  double res_angle;

  // Max range value
  double max_range;

  // Range readings
  int range_count;
  double ranges[GZ_LASER_MAX_RANGES];
  int intensity[GZ_LASER_MAX_RANGES];
  
} gz_laser_data_t;

// The laser interface
typedef struct _gz_laser_t
{
  // General interface info
  gz_iface_t *iface;

  // Pointer to interface data area
  gz_laser_data_t *data;
  
} gz_laser_t;

// Create an interface
extern gz_laser_t *gz_laser_alloc();

// Destroy an interface
extern void gz_laser_free(gz_laser_t *self);

// Create the interface (used by Gazebo server)
extern int gz_laser_create(gz_laser_t *self, gz_server_t *server, const char *id);

// Destroy the interface (server)
extern int gz_laser_destroy(gz_laser_t *self);

// Open an existing interface (used by Gazebo clients)
extern int gz_laser_open(gz_laser_t *self, gz_client_t *client, const char *id);

// Close the interface (client)
extern int gz_laser_close(gz_laser_t *self);

// Lock the interface.  Set blocking to 1 if the caller should block
// until the lock is acquired.  Returns 0 if the lock is acquired.
extern int gz_laser_lock(gz_laser_t *self, int blocking);

// Unlock the interface
extern void gz_laser_unlock(gz_laser_t *self);

10.6 position

The position interface allows clients to send commands to and read odometric data from simulated mobile robot bases, such as the Pioneer2AT or ATRV Jr.

// Position interface
typedef struct _gz_position_data_t
{
  // Common data structures
  gz_data_t head;

  // Data timestamp
  double time;

  // Pose (usually global cs); rotation is specified by euler angles
  double pos[3];
  double rot[3];

  // Velocity; rotation is specified by euler angles
  double vel_pos[3];
  double vel_rot[3];

  // Motor stall flag
  int stall;

  // Enable the motors
  int cmd_enable_motors;

  // Commanded robot velocities (robot cs); rotation is specified by euler angles
  double cmd_vel_pos[3];
  double cmd_vel_rot[3];
  
} gz_position_data_t;

// The position interface
typedef struct _gz_position_t
{
  // General interface info
  gz_iface_t *iface;

  // Pointer to interface data area
  gz_position_data_t *data;
  
} gz_position_t;

// Create an interface
extern gz_position_t *gz_position_alloc();

// Destroy an interface
extern void gz_position_free(gz_position_t *self);

// Create the interface (used by Gazebo server)
extern int gz_position_create(gz_position_t *self, gz_server_t *server, const char *id);

// Destroy the interface (server)
extern int gz_position_destroy(gz_position_t *self);

// Open an existing interface (used by Gazebo clients)
extern int gz_position_open(gz_position_t *self, gz_client_t *client, const char *id);

// Close the interface (client)
extern int gz_position_close(gz_position_t *self);

// Lock the interface.  Set blocking to 1 if the caller should block
// until the lock is acquired.  Returns 0 if the lock is acquired.
extern int gz_position_lock(gz_position_t *self, int blocking);

// Unlock the interface
extern void gz_position_unlock(gz_position_t *self);

10.7 power

The power interface allows clients to read battery levels from simulated robots.

// Power interface
typedef struct _gz_power_data_t
{
  // Common data structures
  gz_data_t head;

  // Data timestamp
  double time;

  // Battery levels (volts)
  double levels[10];
  
} gz_power_data_t;

// The power interface
typedef struct _gz_power_t
{
  // General interface info
  gz_iface_t *iface;

  // Pointer to interface data area
  gz_power_data_t *data;
  
} gz_power_t;

// Create an interface
extern gz_power_t *gz_power_alloc();

// Destroy an interface
extern void gz_power_free(gz_power_t *self);

// Create the interface (used by Gazebo server)
extern int gz_power_create(gz_power_t *self, gz_server_t *server, const char *id);

// Destroy the interface (server)
extern int gz_power_destroy(gz_power_t *self);

// Open an existing interface (used by Gazebo clients)
extern int gz_power_open(gz_power_t *self, gz_client_t *client, const char *id);

// Close the interface (client)
extern int gz_power_close(gz_power_t *self);

// Lock the interface.  Set blocking to 1 if the caller should block
// until the lock is acquired.  Returns 0 if the lock is acquired.
extern int gz_power_lock(gz_power_t *self, int blocking);

// Unlock the interface
extern void gz_power_unlock(gz_power_t *self);

10.8 ptz

The ptz interface allows clients to control the pan, tilt and zoom angles on a camera head such as the Sony VID30.

// Ptz interface
typedef struct _gz_ptz_data_t
{
  // Common data structure
  gz_data_t head;
  
  // Data timestamp
  double time;

  // Measured orientation (radians)
  double pan, tilt;

  // Measured field of view (radians)
  double zoom;

  // Commanded orientation (radians)
  double cmd_pan, cmd_tilt;

  // Commanded field of view (radians)
  double cmd_zoom;
  
} gz_ptz_data_t;

// The ptz interface
typedef struct _gz_ptz_t
{
  // Common data structure
  gz_data_t head;
  
  // General interface info
  gz_iface_t *iface;

  // Pointer to interface data area
  gz_ptz_data_t *data;
  
} gz_ptz_t;

// Create an interface
extern gz_ptz_t *gz_ptz_alloc();

// Destroy an interface
extern void gz_ptz_free(gz_ptz_t *self);

// Create the interface (used by Gazebo server)
extern int gz_ptz_create(gz_ptz_t *self, gz_server_t *server, const char *id);

// Destroy the interface (server)
extern int gz_ptz_destroy(gz_ptz_t *self);

// Open an existing interface (used by Gazebo clients)
extern int gz_ptz_open(gz_ptz_t *self, gz_client_t *client, const char *id);

// Close the interface (client)
extern int gz_ptz_close(gz_ptz_t *self);

// Lock the interface.  Set blocking to 1 if the caller should block
// until the lock is acquired.  Returns 0 if the lock is acquired.
extern int gz_ptz_lock(gz_ptz_t *self, int blocking);

// Unlock the interface
extern void gz_ptz_unlock(gz_ptz_t *self);

10.9 truth

The truth interface is useful for getting and setting the ground-truth pose of objects in the world; currently, it is supported only by the TruthWidget model.

// Truth data
typedef struct _gz_truth_data_t
{
  // Common data structures
  gz_data_t head;

  // Data timestamp
  double time;

  // True object position (x, y, x)
  double pos[3];

  // True object rotation (roll, pitch, yaw)
  double rot[3];

  // New command (0 or 1)?
  int cmd_new;
  
  // Commanded object position
  double cmd_pos[3];

  // Commanded object rotation
  double cmd_rot[3];
   
} gz_truth_data_t;

// The truth interface
typedef struct _gz_truth_t
{
  // General interface info
  gz_iface_t *iface;

  // Pointer to interface data area
  gz_truth_data_t *data;
  
} gz_truth_t;

// Create an interface
extern gz_truth_t *gz_truth_alloc();

// Destroy an interface
extern void gz_truth_free(gz_truth_t *self);

// Create the interface (used by Gazebo server)
extern int gz_truth_create(gz_truth_t *self, gz_server_t *server, const char *id);

// Destroy the interface (server)
extern int gz_truth_destroy(gz_truth_t *self);

// Open an existing interface (used by Gazebo clients)
extern int gz_truth_open(gz_truth_t *self, gz_client_t *client, const char *id);

// Close the interface (client)
extern int gz_truth_close(gz_truth_t *self);

// Lock the interface.  Set blocking to 1 if the caller should block
// until the lock is acquired.  Returns 0 if the lock is acquired.
extern int gz_truth_lock(gz_truth_t *self, int blocking);

// Unlock the interface
extern void gz_truth_unlock(gz_truth_t *self);


next up previous contents
Next: A. Platform Specific Build Up: 2 Developer Guide Previous: 9. libgazebo    Contents
2004-05-31