11 from geometry_msgs.msg 
import Point, Pose, Quaternion, Twist, Wrench
 
   15     rospy.loginfo(
"Waiting for service %s/spawn_sdf_model"%gazebo_namespace)
 
   16     rospy.wait_for_service(gazebo_namespace+
'/spawn_sdf_model')
 
   18       spawn_sdf_model = rospy.ServiceProxy(gazebo_namespace+
'/spawn_sdf_model', SpawnModel)
 
   19       rospy.loginfo(
"Calling service %s/spawn_sdf_model"%gazebo_namespace)
 
   20       resp = spawn_sdf_model(model_name, model_xml, robot_namespace, initial_pose, reference_frame)
 
   21       rospy.loginfo(
"Spawn status: %s"%resp.status_message)
 
   23     except rospy.ServiceException 
as e:
 
   24       print(
"Service call failed: %s" % e)
 
   27     rospy.loginfo(
"Waiting for service %s/spawn_urdf_model"%gazebo_namespace)
 
   28     rospy.wait_for_service(gazebo_namespace+
'/spawn_urdf_model')
 
   30       spawn_urdf_model = rospy.ServiceProxy(gazebo_namespace+
'/spawn_urdf_model', SpawnModel)
 
   31       rospy.loginfo(
"Calling service %s/spawn_urdf_model"%gazebo_namespace)
 
   32       resp = spawn_urdf_model(model_name, model_xml, robot_namespace, initial_pose, reference_frame)
 
   33       rospy.loginfo(
"Spawn status: %s"%resp.status_message)
 
   35     except rospy.ServiceException 
as e:
 
   36       print(
"Service call failed: %s" % e)
 
   39     rospy.loginfo(
"Waiting for service %s/set_model_configuration"%gazebo_namespace)
 
   40     rospy.wait_for_service(gazebo_namespace+
'/set_model_configuration')
 
   41     rospy.loginfo(
"temporary hack to **fix** the -J joint position option (issue #93), sleeping for 1 second to avoid race condition.");
 
   44       set_model_configuration = rospy.ServiceProxy(gazebo_namespace+
'/set_model_configuration', SetModelConfiguration)
 
   45       rospy.loginfo(
"Calling service %s/set_model_configuration"%gazebo_namespace)
 
   46       resp = set_model_configuration(model_name, model_param_name, joint_names, joint_positions)
 
   47       rospy.loginfo(
"Set model configuration status: %s"%resp.status_message)
 
   50     except rospy.ServiceException 
as e:
 
   51       print(
"Service call failed: %s" % e)