|
Modules |
| | Error-handling |
| | Server object |
| | Client object |
| | Common data structures |
| | Common interface structures |
| | simulator |
| | camera |
| | factory |
| | fiducial |
| | guicam |
| | gps |
| | gripper |
| | laser |
| | position |
| | power |
| | ptz |
| | sonar |
| | stereo |
| | truth |
| | wifi |
| | joint |
| | libgazebo |
| gz_wifi_link_t | gz_wifi_data::links [GAZEBO_WIFI_MAX_LINKS] |
| uint16_t | gz_wifi_data::link_count |
Defines |
| #define | LIBGAZEBO_VERSION 0x060 |
| | Interface version number.
|
Variables |
| char * | gz_server::filename |
| | The directory containing mmap files.
|
| int | gz_server::sem_key |
| | The semphore key and id.
|
| int | gz_server::sem_cid |
| int | gz_client::client_id |
| | The client id.
|
| char * | gz_client::filename |
| | The directory containing mmap files.
|
| int | gz_client::sem_key |
| | The semphore key and id.
|
| int | gz_client::sem_cid |
| size_t | gz_data::size |
| | Allocation size.
|
| char | gz_data::model_type [GAZEBO_MAX_MODEL_TYPE] |
| | Type of model that owns this interface.
|
| int | gz_data::model_id |
| | ID of the model that owns this interface.
|
| int | gz_data::parent_model_id |
| | ID of the parent model.
|
| gz_client_t * | gz_iface::client |
| int | gz_iface::mmap_fd |
| void * | gz_iface::mmap |
| char * | gz_iface::filename |
| double | gz_sim_data::sim_time |
| | Elapsed simulator time.
|
| double | gz_sim_data::pause_time |
| double | gz_sim_data::real_time |
| int | gz_sim_data::pause |
| | Pause simulation (set by client).
|
| int | gz_sim_data::reset |
| | Reset simulation (set by client).
|
| int | gz_sim_data::save |
| | Save current poses to world file (set by client).
|
| gz_sim_data_t * | gz_sim::data |
| | Pointer to interface data area.
|
| double | gz_camera_data::time |
| | Data timestamp.
|
| unsigned int | gz_camera_data::width |
| | Image dimensions (in pixels).
|
| unsigned int | gz_camera_data::height |
| unsigned int | gz_camera_data::image_size |
| | Image pixel data.
|
| unsigned char | gz_camera_data::image [GAZEBO_CAMERA_MAX_IMAGE_SIZE] |
| gz_camera_data_t * | gz_camera::data |
| | Pointer to interface data area.
|
| double | gz_factory_data::time |
| | Data timestamp.
|
| uint8_t | gz_factory_data::string [4096] |
| | String describing the model to be instantiated.
|
| gz_factory_data_t * | gz_factory::data |
| | Pointer to interface data area.
|
| double | gz_fiducial_fid::pos [3] |
| | Fiducial position relative to sensor (x, y, z).
|
| double | gz_fiducial_fid::rot [3] |
| | Fiducial orientation relative to sensor (roll, pitch, yaw).
|
| double | gz_fiducial_data::time |
| | Data timestamp.
|
| int | gz_fiducial_data::fid_count |
| | Observed fiducials.
|
| gz_fiducial_fid_t | gz_fiducial_data::fids [GZ_FIDUCIAL_MAX_FIDS] |
| gz_fiducial_data_t * | gz_fiducial::data |
| | Pointer to interface data area.
|
| double | gz_guicam_data::sim_time |
| | Data timestamp (simulator time).
|
| double | gz_guicam_data::pause_time |
| 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] |
| int | gz_guicam_data::roll_lock |
| 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 |
| 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 |
| gz_guicam_data_t * | gz_guicam::data |
| | Pointer to interface data area.
|
| double | gz_gps_data::time |
| | Data timestamp.
|
| double | gz_gps_data::utc_time |
| | UTC timestamp.
|
| double | gz_gps_data::latitude |
| | Latitude in degrees.
|
| double | gz_gps_data::longitude |
| | Longitude in degrees.
|
| double | gz_gps_data::altitude |
| | Altitude, in meters.
|
| double | gz_gps_data::utm_e |
| | UTM coordinates (meters).
|
| double | gz_gps_data::utm_n |
| int | gz_gps_data::satellites |
| | Number of satellites in view.
|
| int | gz_gps_data::quality |
| | Fix quality.
|
| double | gz_gps_data::hdop |
| | Horizontal dilution of position (HDOP).
|
| double | gz_gps_data::vdop |
| | Vertical dilution of position (VDOP).
|
| double | gz_gps_data::err_horz |
| | Errors.
|
| double | gz_gps_data::err_vert |
| gz_gps_data_t * | gz_gps::data |
| | Pointer to interface data area.
|
| double | gz_gripper_data::time |
| | Data timestamp.
|
| int | gz_gripper_data::cmd |
| int | gz_gripper_data::lift_limit_reach |
| int | gz_gripper_data::grip_limit_reach |
| int | gz_gripper_data::outer_beam_obstruct |
| int | gz_gripper_data::inner_beam_obstruct |
| int | gz_gripper_data::left_paddle_open |
| int | gz_gripper_data::right_paddle_open |
| int | gz_gripper_data::paddles_opened |
| int | gz_gripper_data::paddles_closed |
| int | gz_gripper_data::paddles_moving |
| int | gz_gripper_data::paddles_error |
| int | gz_gripper_data::lift_up |
| int | gz_gripper_data::lift_down |
| int | gz_gripper_data::lift_moving |
| int | gz_gripper_data::lift_error |
| gz_gripper_data_t * | gz_gripper::data |
| | Pointer to interface data area.
|
| double | gz_laser_data::time |
| | Data timestamp.
|
| double | gz_laser_data::min_angle |
| | Range scan angles.
|
| double | gz_laser_data::max_angle |
| double | gz_laser_data::res_angle |
| | Angular resolution.
|
| double | gz_laser_data::max_range |
| | Max range value.
|
| int | gz_laser_data::range_count |
| | Number of range readings.
|
| double | gz_laser_data::ranges [GZ_LASER_MAX_RANGES] |
| | Range readings.
|
| int | gz_laser_data::intensity [GZ_LASER_MAX_RANGES] |
| | Intensity readings.
|
| int | gz_laser_data::cmd_new_angle |
| int | gz_laser_data::cmd_new_length |
| double | gz_laser_data::cmd_max_range |
| double | gz_laser_data::cmd_min_angle |
| double | gz_laser_data::cmd_max_angle |
| int | gz_laser_data::cmd_range_count |
| gz_laser_data_t * | gz_laser::data |
| | Pointer to interface data area.
|
| double | gz_position_data::time |
| | Data timestamp.
|
| double | gz_position_data::pos [3] |
| | Pose (usually global cs); rotation is specified by euler angles.
|
| double | gz_position_data::rot [3] |
| double | gz_position_data::vel_pos [3] |
| | Velocity; rotation is specified by euler angles.
|
| double | gz_position_data::vel_rot [3] |
| int | gz_position_data::stall |
| | Motor stall flag.
|
| int | gz_position_data::cmd_enable_motors |
| | Enable the motors.
|
| double | gz_position_data::cmd_vel_pos [3] |
| | Commanded robot velocities (robot cs); rotation is specified by euler angles.
|
| double | gz_position_data::cmd_vel_rot [3] |
| gz_position_data_t * | gz_position::data |
| | Pointer to interface data area.
|
| double | gz_power_data::time |
| | Data timestamp.
|
| double | gz_power_data::levels [10] |
| | Battery levels (volts).
|
| gz_power_data_t * | gz_power::data |
| | Pointer to interface data area.
|
| double | gz_ptz_data::time |
| | Data timestamp.
|
| double | gz_ptz_data::pan |
| | Measured orientation (radians).
|
| double | gz_ptz_data::tilt |
| double | gz_ptz_data::zoom |
| | Measured field of view (radians).
|
| double | gz_ptz_data::cmd_pan |
| | Commanded orientation (radians).
|
| double | gz_ptz_data::cmd_tilt |
| double | gz_ptz_data::cmd_zoom |
| | Commanded field of view (radians).
|
| gz_iface_t * | gz_ptz::iface |
| | General interface info.
|
| gz_ptz_data_t * | gz_ptz::data |
| | Pointer to interface data area.
|
| double | gz_sonar_data::time |
| | Data timestamp.
|
| double | gz_sonar_data::max_range |
| | Max range value.
|
| int | gz_sonar_data::sonar_count |
| | Number of sonar.
|
| double | gz_sonar_data::sonar_pos [GZ_SONAR_MAX_RANGES][3] |
| | Position of each sonar (x, y, z).
|
| double | gz_sonar_data::sonar_rot [GZ_SONAR_MAX_RANGES][3] |
| | Orientation of each soanr (roll, pitch, yaw).
|
| double | gz_sonar_data::sonar_ranges [GZ_SONAR_MAX_RANGES] |
| | Range readings (m).
|
| int | gz_sonar_data::cmd_enable_sonar |
| | Enable the sonars.
|
| gz_sonar_data_t * | gz_sonar::data |
| | Pointer to interface data area.
|
| double | gz_stereo_data::time |
| | Data timestamp.
|
| unsigned int | gz_stereo_data::width |
| | Image dimensions (in pixels).
|
| unsigned int | gz_stereo_data::height |
| unsigned int | gz_stereo_data::left_image_size |
| | Left image (packed RGB888).
|
| unsigned char | gz_stereo_data::left_image [GAZEBO_STEREO_MAX_RGB_SIZE] |
| unsigned int | gz_stereo_data::right_image_size |
| | Right image (packed RGB888).
|
| unsigned char | gz_stereo_data::right_image [GAZEBO_STEREO_MAX_RGB_SIZE] |
| unsigned int | gz_stereo_data::left_disparity_size |
| | Left disparity image (packed float).
|
| float | gz_stereo_data::left_disparity [GAZEBO_STEREO_MAX_DISPARITY_SIZE] |
| unsigned int | gz_stereo_data::right_disparity_size |
| | Right disparity image (packed float).
|
| float | gz_stereo_data::right_disparity [GAZEBO_STEREO_MAX_DISPARITY_SIZE] |
| gz_stereo_data_t * | gz_stereo::data |
| | Pointer to interface data area.
|
| double | gz_truth_data::time |
| | Data timestamp.
|
| double | gz_truth_data::pos [3] |
| | True object position (x, y, z).
|
| double | gz_truth_data::rot [4] |
| | True object rotation (quaternion: u,x,y,z).
|
| int | gz_truth_data::cmd_new |
| | New command (0 or 1)?
|
| double | gz_truth_data::cmd_pos [3] |
| | Commanded object position (x, y, z).
|
| double | gz_truth_data::cmd_rot [4] |
| | Commanded object rotation (quaternion: u,x,y,z).
|
| gz_truth_data_t * | gz_truth::data |
| | Pointer to interface data area.
|
| uint16_t | gz_wifi_link::qual |
| uint16_t | gz_wifi_link::level |
| uint16_t | gz_wifi_link::noise |
| double | gz_wifi_data::time |
| | Data timestamp.
|
| gz_wifi_data_t * | gz_wifi::data |
| | Pointer to interface data area.
|
| double | gz_joint_data::anchor [3] |
| | Anchor vector.
|
| double | gz_joint_data::axis [3] |
| | First axis.
|
| double | gz_joint_data::axis2 [3] |
| | Second axis, for Universal and Hinge2 joints.
|
| double | gz_joint_data::angular_velocity |
| | Angular velocity about first axis.
|
| double | gz_joint_data::angular_velocity2 |
| | Angular velocity about second axis.
|
| double | gz_joint_data::angle |
| | Angle of first axis.
|
| double | gz_joint_data::angle2 |
| | Angle of second axis.
|
| double | gz_joint_data::cmd_angle |
| | Commanded angle for the first axis.
|
| double | gz_joint_data::cmd_angle2 |
| | Commanded angle for the second axis.
|
| double | gz_joints::time |
| | Data timestamp.
|
| gz_joint_data_t | gz_joints::joints [GAZEBO_JOINT_MAX_JOINTS] |
| int | gz_joints::joint_count |
| gz_joints_t * | gz_joint::data |
| | Pointer to interface data area.
|
for information on using libgazebo.