gazebo_msgs¶
Contents:
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¶
Service types¶
gazebo_msgs/ApplyBodyWrench
gazebo_msgs/GetLinkProperties
gazebo_msgs/SetJointProperties
gazebo_msgs/GetLinkState
gazebo_msgs/GetJointProperties
gazebo_msgs/SpawnModel
gazebo_msgs/BodyRequest
gazebo_msgs/SetLinkProperties
gazebo_msgs/JointRequest
gazebo_msgs/GetWorldProperties
gazebo_msgs/SetModelState
gazebo_msgs/GetPhysicsProperties
gazebo_msgs/GetModelState
gazebo_msgs/SetPhysicsProperties
gazebo_msgs/DeleteModel
gazebo_msgs/ApplyJointEffort
gazebo_msgs/SetModelConfiguration
gazebo_msgs/SetJointTrajectory
gazebo_msgs/SetLinkState
gazebo_msgs/GetModelProperties
-
gazebo_msgs/ApplyBodyWrench
¶ Field (Request): - body_name (string) –
- reference_frame (string) –
- reference_point (geometry_msgs/Point) –
- wrench (geometry_msgs/Wrench) –
- start_time (time) –
- duration (duration) –
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): - joint_name (string) –
- ode_joint_config (gazebo_msgs/ODEJointProperties) –
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): - link_state (gazebo_msgs/LinkState) –
- success (bool) –
- status_message (string) –
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): - model_state (gazebo_msgs/ModelState) –
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): - time_step (float64) –
- pause (bool) –
- max_update_rate (float64) –
- gravity (geometry_msgs/Vector3) –
- ode_config (gazebo_msgs/ODEPhysics) –
- 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 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): - pose (geometry_msgs/Pose) –
- twist (geometry_msgs/Twist) –
- success (bool) –
- status_message (string) –
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): - time_step (float64) –
- max_update_rate (float64) –
- gravity (geometry_msgs/Vector3) –
- ode_config (gazebo_msgs/ODEPhysics) –
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): - model_name (string) –
- joint_trajectory (trajectory_msgs/JointTrajectory) –
- model_pose (geometry_msgs/Pose) –
- set_model_pose (bool) –
- disable_physics_updates (bool) –
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): - link_state (gazebo_msgs/LinkState) –
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