File: gazebo_plugins/SpawnModel.srv
gazebo_plugins/GazeboModel model # message containing a model for spawning
---
bool success # return true if spawn successful
string status_message # comments if available
Expanded Definition
gazebo_plugins/GazeboModel model
uint32 disable_urdf_joint_limits=0
uint32 URDF=0
uint32 GAZEBO_XML=1
uint32 URDF_PARAM_NAME=2
uint32 GAZEBO_XML_PARAM_NAME=3
uint32 URDF_FILE_NAME=4
uint32 GAZEBO_XML_FILE_NAME=5
string model_name
string robot_model
uint32 xml_type
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
bool success
string status_message