gazebo/SpawnModel Service

File: gazebo/SpawnModel.srv

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

Expanded Definition

string model_name
string model_xml
string robot_namespace
geometry_msgs/Pose initial_pose
    geometry_msgs/Point position
        float64 x
        float64 y
        float64 z
    geometry_msgs/Quaternion orientation
        float64 x
        float64 y
        float64 z
        float64 w
string reference_frame

bool success
string status_message