gazebo_msgs

Summary

gazebo_msgs
Version:

2.5.1

Description:

Message and service data structures for interacting with Gazebo from ROS.

Maintainers:
  • John Hsu <hsu AT osrfoundation DOT org>
Licenses:
  • BSD
Urls:
Authors:
  • John Hsu
BuildDepends:
BuildtoolDepends:
 
BuildExportDepends:
 
ExecDepends:

Types

Message types

gazebo_msgs/WorldState
Field:

This is a message that holds data necessary to reconstruct a snapshot of the world

= Approach to Message Passing = The state of the world is defined by either

  1. Inertial Model pose, twist * kinematic data - connectivity graph from Model to each Link * joint angles * joint velocities * Applied forces - Body wrench

    • relative transform from Body to each collision Geom
Or
  1. Inertial (absolute) Body pose, twist, wrench * relative transform from Body to each collision Geom - constant, so not sent over wire * back compute from canonical body info to get Model pose and twist.
Chooing (2.) because it matches most physics engines out there
and is simpler.

= Future = Consider impacts on using reduced coordinates / graph (parent/child links) approach

constraint and physics solvers.

= Application = This message is used to do the following:

  • reconstruct the world and objects for sensor generation
  • stop / start simulation - need pose, twist, wrench of each body
  • collision detection - need pose of each collision geometry. velocity/acceleration if

= Assumptions = Assuming that each (physics) processor node locally already has

  • collision information - Trimesh for Geoms, etc
  • relative transforms from Body to Geom - this is assumed to be fixed, do not send oved wire
  • inertial information - does not vary in time
  • visual information - does not vary in time
# This is a message that holds data necessary to reconstruct a snapshot of the world
#
# = Approach to Message Passing =
# The state of the world is defined by either
#   1. Inertial Model pose, twist
#      * kinematic data - connectivity graph from Model to each Link
#      * joint angles
#      * joint velocities
#      * Applied forces - Body wrench
#        * relative transform from Body to each collision Geom
# Or
#   2. Inertial (absolute) Body pose, twist, wrench
#      * relative transform from Body to each collision Geom - constant, so not sent over wire
#      * back compute from canonical body info to get Model pose and twist.
#
# Chooing (2.) because it matches most physics engines out there
#   and is simpler.
#
# = Future =
# Consider impacts on using reduced coordinates / graph (parent/child links) approach
#   constraint and physics solvers.
#
# = Application =
# This message is used to do the following:
#   * reconstruct the world and objects for sensor generation
#   * stop / start simulation - need pose, twist, wrench of each body
#   * collision detection - need pose of each collision geometry.  velocity/acceleration if 
#
# = Assumptions =
# Assuming that each (physics) processor node locally already has
#   * collision information - Trimesh for Geoms, etc
#   * relative transforms from Body to Geom - this is assumed to be fixed, do not send oved wire
#   * inertial information - does not vary in time
#   * visual information - does not vary in time
#

Header header

string[] name
geometry_msgs/Pose[] pose
geometry_msgs/Twist[] twist
geometry_msgs/Wrench[] wrench
gazebo_msgs/ODEJointProperties
Field:
  • damping[] (float64) –
  • hiStop[] (float64) –
  • loStop[] (float64) –
  • erp[] (float64) –
  • cfm[] (float64) –
  • stop_erp[] (float64) –
  • stop_cfm[] (float64) –
  • fudge_factor[] (float64) –
  • fmax[] (float64) –
  • vel[] (float64) –

access to low level joint properties, change these at your own risk

# access to low level joint properties, change these at your own risk
float64[] damping             # joint damping
float64[] hiStop              # joint limit
float64[] loStop              # joint limit
float64[] erp                 # set joint erp
float64[] cfm                 # set joint cfm
float64[] stop_erp            # set joint erp for joint limit "contact" joint
float64[] stop_cfm            # set joint cfm for joint limit "contact" joint
float64[] fudge_factor        # joint fudge_factor applied at limits, see ODE manual for info.
float64[] fmax                # ode joint param fmax
float64[] vel                 # ode joint param vel
gazebo_msgs/ContactState
Field:
string info                                   # text info on this contact
string collision1_name                        # name of contact collision1
string collision2_name                        # name of contact collision2
geometry_msgs/Wrench[] wrenches               # list of forces/torques
geometry_msgs/Wrench total_wrench             # sum of forces/torques in every DOF
geometry_msgs/Vector3[] contact_positions     # list of contact position
geometry_msgs/Vector3[] contact_normals       # list of contact normals
float64[] depths                              # list of penetration depths
gazebo_msgs/ODEPhysics
Field:
  • auto_disable_bodies (bool) –
  • sor_pgs_precon_iters (uint32) –
  • sor_pgs_iters (uint32) –
  • sor_pgs_w (float64) –
  • sor_pgs_rms_error_tol (float64) –
  • contact_surface_layer (float64) –
  • contact_max_correcting_vel (float64) –
  • cfm (float64) –
  • erp (float64) –
  • max_contacts (uint32) –
bool auto_disable_bodies           # enable auto disabling of bodies, default false
uint32 sor_pgs_precon_iters        # preconditioning inner iterations when uisng projected Gauss Seidel
uint32 sor_pgs_iters               # inner iterations when uisng projected Gauss Seidel
float64 sor_pgs_w                  # relaxation parameter when using projected Gauss Seidel, 1 = no relaxation
float64 sor_pgs_rms_error_tol      # rms error tolerance before stopping inner iterations
float64 contact_surface_layer      # contact "dead-band" width
float64 contact_max_correcting_vel # contact maximum correction velocity
float64 cfm                        # global constraint force mixing
float64 erp                        # global error reduction parameter
uint32 max_contacts                # maximum contact joints between two geoms
gazebo_msgs/ContactsState
Field:
Header header                                   # stamp
gazebo_msgs/ContactState[] states            # array of geom pairs in contact
gazebo_msgs/ModelStates
Field:

broadcast all model states in world frame

# broadcast all model states in world frame
string[] name                 # model names
geometry_msgs/Pose[] pose     # desired pose in world frame
geometry_msgs/Twist[] twist   # desired twist in world frame
gazebo_msgs/LinkState
Field:

@todo: FIXME: sets pose and twist of a link. All children link poses/twists of the URDF tree are not updated accordingly, but should be.

# @todo: FIXME: sets pose and twist of a link.  All children link poses/twists of the URDF tree are not updated accordingly, but should be.
string link_name            # link name, link_names are in gazebo scoped name notation, [model_name::body_name]
geometry_msgs/Pose pose     # desired pose in reference frame
geometry_msgs/Twist twist   # desired twist in reference frame
string reference_frame      # set pose/twist relative to the frame of this link/body
                            # leave empty or "world" or "map" defaults to world-frame
gazebo_msgs/LinkStates
Field:

broadcast all link states in world frame

# broadcast all link states in world frame
string[] name                 # link names
geometry_msgs/Pose[] pose     # desired pose in world frame
geometry_msgs/Twist[] twist   # desired twist in world frame
gazebo_msgs/ModelState
Field:

Set Gazebo Model pose and twist

# Set Gazebo Model pose and twist
string model_name           # model to set state (pose and twist)
geometry_msgs/Pose pose     # desired pose in reference frame
geometry_msgs/Twist twist   # desired twist in reference frame
string reference_frame      # set pose/twist relative to the frame of this entity (Body/Model)
                            # leave empty or "world" or "map" defaults to world-frame

Service types

gazebo_msgs/ApplyBodyWrench
Field (Request):
 
Field (Response):
 
  • success (bool) –
  • status_message (string) –

Apply Wrench to Gazebo Body. via the callback mechanism all Gazebo operations are made in world frame

# Apply Wrench to Gazebo Body.
# via the callback mechanism
# all Gazebo operations are made in world frame
string body_name                          # Gazebo body to apply wrench (linear force and torque)
                                          # wrench is applied in the gazebo world by default
                                          # body names are prefixed by model name, e.g. pr2::base_link
string reference_frame                    # wrench is defined in the reference frame of this entity
                                          # use inertial frame if left empty
                                          # frame names are bodies prefixed by model name, e.g. pr2::base_link
geometry_msgs/Point  reference_point      # wrench is defined at this location in the reference frame
geometry_msgs/Wrench wrench               # wrench applied to the origin of the body
time start_time                           # (optional) wrench application start time (seconds)
                                          # if start_time is not specified, or
                                          # start_time < current time, start as soon as possible
duration duration                         # optional duration of wrench application time (seconds)
                                          # if duration < 0, apply wrench continuously without end
                                          # if duration = 0, do nothing
                                          # if duration < step size, apply wrench
                                          # for one step size
---
bool success                              # return true if set wrench successful
string status_message                     # comments if available
gazebo_msgs/GetLinkProperties
Field (Request):
 
  • link_name (string) –
Field (Response):
 
  • com (geometry_msgs/Pose) –
  • gravity_mode (bool) –
  • mass (float64) –
  • ixx (float64) –
  • ixy (float64) –
  • ixz (float64) –
  • iyy (float64) –
  • iyz (float64) –
  • izz (float64) –
  • success (bool) –
  • status_message (string) –
string link_name          # name of link
                          # link names are prefixed by model name, e.g. pr2::base_link
---
geometry_msgs/Pose com    # center of mass location in link frame
                          # and orientation of the moment of inertias
                          # relative to the link frame
bool gravity_mode         # set gravity mode on/off
float64 mass              # linear mass of link
float64 ixx               # moment of inertia
float64 ixy               # moment of inertia
float64 ixz               # moment of inertia
float64 iyy               # moment of inertia
float64 iyz               # moment of inertia
float64 izz               # moment of inertia
bool success              # return true if get info is successful
string status_message     # comments if available
gazebo_msgs/SetJointProperties
Field (Request):
 
Field (Response):
 
  • success (bool) –
  • status_message (string) –
string joint_name                               # name of joint
gazebo_msgs/ODEJointProperties ode_joint_config # access to ODE joint dynamics properties
---
bool success                                    # return true if get successful
string status_message                           # comments if available
gazebo_msgs/GetLinkState
Field (Request):
 
  • link_name (string) –
  • reference_frame (string) –
Field (Response):
 
string link_name          # name of link
                          # link names are prefixed by model name, e.g. pr2::base_link
string reference_frame    # reference frame of returned information, must be a valid link
                          # if empty, use inertial (gazebo world) frame
                          # reference_frame names are prefixed by model name, e.g. pr2::base_link
---
gazebo_msgs/LinkState link_state
bool success              # return true if get info is successful
string status_message     # comments if available
gazebo_msgs/GetJointProperties
Field (Request):
 
  • joint_name (string) –
Field (Response):
 
  • type (uint8) –
  • damping[] (float64) –
  • position[] (float64) –
  • rate[] (float64) –
  • success (bool) –
  • status_message (string) –
Constant (Response):
 
  • REVOLUTE (uint8):0
  • CONTINUOUS (uint8):1
  • PRISMATIC (uint8):2
  • FIXED (uint8):3
  • BALL (uint8):4
  • UNIVERSAL (uint8):5
string joint_name                    # name of joint
---
# joint type
uint8 type
uint8 REVOLUTE    = 0                # single DOF
uint8 CONTINUOUS  = 1                # single DOF (revolute w/o joints)
uint8 PRISMATIC   = 2                # single DOF
uint8 FIXED       = 3                # 0 DOF
uint8 BALL        = 4                # 3 DOF
uint8 UNIVERSAL   = 5                # 2 DOF
# dynamics properties
float64[] damping
# joint state
float64[] position
float64[] rate
# service return status
bool success                         # return true if get successful
string status_message                # comments if available
gazebo_msgs/SpawnModel
Field (Request):
 
  • model_name (string) –
  • model_xml (string) –
  • robot_namespace (string) –
  • initial_pose (geometry_msgs/Pose) –
  • reference_frame (string) –
Field (Response):
 
  • success (bool) –
  • status_message (string) –
string model_name                 # name of the model to be spawn
string model_xml                  # this should be an urdf or gazebo xml
string robot_namespace            # spawn robot and all ROS interfaces under this namespace
geometry_msgs/Pose initial_pose   # only applied to canonical body
string reference_frame            # initial_pose is defined relative to the frame of this model/body
                                  # if left empty or "world", then gazebo world frame is used
                                  # if non-existent model/body is specified, an error is returned
                                  #   and the model is not spawned
---
bool success                      # return true if spawn successful
string status_message             # comments if available
gazebo_msgs/BodyRequest
Field (Request):
 
  • body_name (string) –
string body_name   # name of the body requested. body names are prefixed by model name, e.g. pr2::base_link
---
gazebo_msgs/SetLinkProperties
Field (Request):
 
  • link_name (string) –
  • com (geometry_msgs/Pose) –
  • gravity_mode (bool) –
  • mass (float64) –
  • ixx (float64) –
  • ixy (float64) –
  • ixz (float64) –
  • iyy (float64) –
  • iyz (float64) –
  • izz (float64) –
Field (Response):
 
  • success (bool) –
  • status_message (string) –
string link_name          # name of link
                          # link names are prefixed by model name, e.g. pr2::base_link
geometry_msgs/Pose com    # center of mass location in link frame
                          # and orientation of the moment of inertias
                          # relative to the link frame
bool gravity_mode         # set gravity mode on/off
float64 mass              # linear mass of link
float64 ixx               # moment of inertia
float64 ixy               # moment of inertia
float64 ixz               # moment of inertia
float64 iyy               # moment of inertia
float64 iyz               # moment of inertia
float64 izz               # moment of inertia
---
bool success              # return true if get info is successful
string status_message     # comments if available
gazebo_msgs/JointRequest
Field (Request):
 
  • joint_name (string) –
string joint_name   # name of the joint requested
---
gazebo_msgs/GetWorldProperties
Field (Response):
 
  • sim_time (float64) –
  • model_names[] (string) –
  • rendering_enabled (bool) –
  • success (bool) –
  • status_message (string) –
---
float64 sim_time                     # current sim time
string[] model_names                 # list of models in the world
bool rendering_enabled               # if X is used
bool success                         # return true if get successful
string status_message                # comments if available
gazebo_msgs/SetModelState
Field (Request):
 
Field (Response):
 
  • success (bool) –
  • status_message (string) –
gazebo_msgs/ModelState model_state
---
bool success                  # return true if setting state successful
string status_message         # comments if available
gazebo_msgs/GetPhysicsProperties
Field (Response):
 
---
# sets pose and twist of a link.  All children link poses/twists of the URDF tree will be updated accordingly
float64 time_step                  # dt in seconds
bool pause                         # true if physics engine is paused
float64 max_update_rate            # throttle maximum physics update rate
geometry_msgs/Vector3 gravity      # gravity vector (e.g. earth ~[0,0,-9.81])
gazebo_msgs/ODEPhysics ode_config  # contains physics configurations pertaining to ODE
bool success                       # return true if set wrench successful
string status_message              # comments if available
gazebo_msgs/GetModelState
Field (Request):
 
  • model_name (string) –
  • relative_entity_name (string) –
Field (Response):
 
string model_name                    # name of Gazebo Model
string relative_entity_name          # return pose and twist relative to this entity
                                     # an entity can be a model, body, or geom
                                     # be sure to use gazebo scoped naming notation (e.g. [model_name::body_name])
                                     # leave empty or "world" will use inertial world frame
---
geometry_msgs/Pose pose              # pose of model in relative entity frame
geometry_msgs/Twist twist            # twist of model in relative entity frame
bool success                         # return true if get successful
string status_message                # comments if available
gazebo_msgs/SetPhysicsProperties
Field (Request):
 
Field (Response):
 
  • success (bool) –
  • status_message (string) –

sets pose and twist of a link. All children link poses/twists of the URDF tree will be updated accordingly

# sets pose and twist of a link.  All children link poses/twists of the URDF tree will be updated accordingly
float64 time_step                  # dt in seconds
float64 max_update_rate            # throttle maximum physics update rate
geometry_msgs/Vector3 gravity      # gravity vector (e.g. earth ~[0,0,-9.81])
gazebo_msgs/ODEPhysics ode_config  # configurations for ODE
---
bool success                       # return true if set wrench successful
string status_message              # comments if available
gazebo_msgs/DeleteModel
Field (Request):
 
  • model_name (string) –
Field (Response):
 
  • success (bool) –
  • status_message (string) –
string model_name                 # name of the Gazebo Model to be deleted
---
bool success                      # return true if deletion is successful
string status_message             # comments if available
gazebo_msgs/ApplyJointEffort
Field (Request):
 
  • joint_name (string) –
  • effort (float64) –
  • start_time (time) –
  • duration (duration) –
Field (Response):
 
  • success (bool) –
  • status_message (string) –

set urdf joint effort

# set urdf joint effort
string joint_name           # joint to apply wrench (linear force and torque)
float64 effort              # effort to apply
time start_time             # optional wrench application start time (seconds)
                            # if start_time < current time, start as soon as possible
duration duration           # optional duration of wrench application time (seconds)
                            # if duration < 0, apply wrench continuously without end
                            # if duration = 0, do nothing
                            # if duration < step size, assume step size and
                            #               display warning in status_message
---
bool success                # return true if effort application is successful
string status_message       # comments if available
gazebo_msgs/SetModelConfiguration
Field (Request):
 
  • model_name (string) –
  • urdf_param_name (string) –
  • joint_names[] (string) –
  • joint_positions[] (float64) –
Field (Response):
 
  • success (bool) –
  • status_message (string) –

Set Gazebo Model pose and twist

# Set Gazebo Model pose and twist
string model_name           # model to set state (pose and twist)
string urdf_param_name      # parameter name that contains the urdf XML.

string[] joint_names        # list of joints to set positions.  if joint is not listed here, preserve current position.
float64[] joint_positions   # set to this position.
---
bool success                # return true if setting state successful
string status_message       # comments if available
gazebo_msgs/SetJointTrajectory
Field (Request):
 
Field (Response):
 
  • success (bool) –
  • status_message (string) –
string model_name
trajectory_msgs/JointTrajectory joint_trajectory
geometry_msgs/Pose model_pose
bool set_model_pose
bool disable_physics_updates # defaults to false
---
bool success                # return true if set wrench successful
string status_message       # comments if available
gazebo_msgs/SetLinkState
Field (Request):
 
Field (Response):
 
  • success (bool) –
  • status_message (string) –
gazebo_msgs/LinkState link_state
---
bool success                # return true if set wrench successful
string status_message       # comments if available
gazebo_msgs/GetModelProperties
Field (Request):
 
  • model_name (string) –
Field (Response):
 
  • parent_model_name (string) –
  • canonical_body_name (string) –
  • body_names[] (string) –
  • geom_names[] (string) –
  • joint_names[] (string) –
  • child_model_names[] (string) –
  • is_static (bool) –
  • success (bool) –
  • status_message (string) –
string model_name                    # name of Gazebo Model
---
string parent_model_name             # parent model
string canonical_body_name           # name of canonical body, body names are prefixed by model name, e.g. pr2::base_link
string[] body_names                  # list of bodies, body names are prefixed by model name, e.g. pr2::base_link
string[] geom_names                  # list of geoms
string[] joint_names                 # list of joints attached to the model
string[] child_model_names           # list of child models
bool is_static                       # returns true if model is static
bool success                         # return true if get successful
string status_message                # comments if available