Home
FAQ
Player
Utilities
Stage
Gazebo
Contrib
Documentation
Publications
Contributors
Users

Project
Download
Bugs/Feedback
Mailing lists

Radish

Old news
Old stuff

gz_guicam_data Struct Reference
[guicam]

Guicam interface data. More...

#include <gazebo.h>

List of all members.

Public Attributes

gz_data_t head
 Common data structure.
double sim_time
 Data timestamp (simulator time).
double pause_time
double pos [3]
 True object position (x, y, x).
double rot [3]
 True object rotation (roll, pitch, yaw).
int cmd_spot_mode
 Spot mode (0 = translate; 1 = zoom; 2 = rotate).
int cmd_spot_state
 Spot state (0 = none; 1 = moving).
double cmd_spot_a [2]
 Spot transform points (image coordinates).
double cmd_spot_b [2]
 Spot transform points (image coordinates).
int roll_lock
int display_bbox
 Display bounding boxes.
int display_axes
 Display body axes.
int display_com
 Display CoM axes.
int display_skins
 Display skins.
int display_rays
 Display sensor rays.
int display_frustrums
 Display sensor frustrums.
int display_materials
 Display materials.
int display_textures
 Display textures.
int polygon_fill
 Polygon mode: 0 = wireframe, 1 = filled.
int shade_smooth
 Shade model: 0 = flat, 1 = smooth.
int save_frames
 Save frames to disk.
unsigned int width
 Image dimensions (in pixels).
unsigned int height
 Image dimensions (in pixels).
unsigned char image [GAZEBO_GUICAM_MAX_IMAGE_SIZE]
 Image pixel data; format is packed RGB888.
unsigned int image_size


Detailed Description

Guicam interface data.


Member Data Documentation

gz_data_t gz_guicam_data::head
 

Common data structure.

double gz_guicam_data::sim_time
 

Data timestamp (simulator time).

double gz_guicam_data::pause_time
 

Accumpated pause time (this interface may be updated with the server is paused).

double gz_guicam_data::pos[3]
 

True object position (x, y, x).

double gz_guicam_data::rot[3]
 

True object rotation (roll, pitch, yaw).

int gz_guicam_data::cmd_spot_mode
 

Spot mode (0 = translate; 1 = zoom; 2 = rotate).

int gz_guicam_data::cmd_spot_state
 

Spot state (0 = none; 1 = moving).

double gz_guicam_data::cmd_spot_a[2]
 

Spot transform points (image coordinates).

double gz_guicam_data::cmd_spot_b[2]
 

Spot transform points (image coordinates).

int gz_guicam_data::roll_lock
 

Lock the roll (so that the image y axis corresponds to world z axis)

int gz_guicam_data::display_bbox
 

Display bounding boxes.

int gz_guicam_data::display_axes
 

Display body axes.

int gz_guicam_data::display_com
 

Display CoM axes.

int gz_guicam_data::display_skins
 

Display skins.

int gz_guicam_data::display_rays
 

Display sensor rays.

int gz_guicam_data::display_frustrums
 

Display sensor frustrums.

int gz_guicam_data::display_materials
 

Display materials.

int gz_guicam_data::display_textures
 

Display textures.

int gz_guicam_data::polygon_fill
 

Polygon mode: 0 = wireframe, 1 = filled.

int gz_guicam_data::shade_smooth
 

Shade model: 0 = flat, 1 = smooth.

int gz_guicam_data::save_frames
 

Save frames to disk.

unsigned int gz_guicam_data::width
 

Image dimensions (in pixels).

unsigned int gz_guicam_data::height
 

Image dimensions (in pixels).

unsigned char gz_guicam_data::image[GAZEBO_GUICAM_MAX_IMAGE_SIZE]
 

Image pixel data; format is packed RGB888.

unsigned int gz_guicam_data::image_size
 


The documentation for this struct was generated from the following file:


Last updated $Date: 2004/12/21 01:49:15 $
Generated on Sun May 22 18:39:08 2005 for Gazebo by doxygen 1.4.2