Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048
00049
00050
00051
00052
00053
00054
00055
00056
00057
00058
00059 import sys
00060 import roslib
00061 roslib.load_manifest('cob_bringup_sim')
00062
00063 import rospy
00064 import os
00065
00066 from gazebo.srv import *
00067 from geometry_msgs.msg import *
00068 import tf.transformations as tft
00069
00070 if __name__ == "__main__":
00071 if len(sys.argv) < 2:
00072 print '[spawn_object.py] Please specify the names of the objects to be loaded'
00073 sys.exit()
00074
00075 rospy.init_node("object_spawner")
00076
00077
00078 if not rospy.has_param("/objects"):
00079 rospy.logerr("No objects uploaded to /objects")
00080 sys.exit()
00081 all_object_names = rospy.get_param("/objects").keys()
00082
00083
00084 if "all" in sys.argv:
00085 object_names = all_object_names
00086 else:
00087 object_names = sys.argv
00088 object_names.pop(0)
00089
00090 rospy.loginfo("Trying to spawn %s",object_names)
00091
00092 for name in object_names:
00093
00094 if not rospy.has_param("/objects/%s" % name):
00095 rospy.logerr("No description for " + name + " found at /objects/" + name)
00096 continue
00097
00098
00099 if not rospy.has_param("/objects/%s/model" % name):
00100 rospy.logerr("No model for " + name + " found at /objects/" + name + "/model")
00101 continue
00102 model = rospy.get_param("/objects/%s/model" % name)
00103
00104
00105 if not rospy.has_param("/objects/%s/model_type" % name):
00106 rospy.logerr("No model_type for " + name + " found at /objects/" + name + "/model_type")
00107 continue
00108 model_type = rospy.get_param("/objects/%s/model_type" % name)
00109
00110
00111 if not rospy.has_param("/objects/%s/position" % name):
00112 rospy.logerr("No position for " + name + " found at /objects/" + name + "/position")
00113 continue
00114 position = rospy.get_param("/objects/%s/position" % name)
00115
00116
00117 if not rospy.has_param("/objects/%s/orientation" % name):
00118 rospy.logerr("No orientation for " + name + " found at /objects/" + name + "/orientation")
00119 continue
00120
00121 orientation = rospy.get_param("/objects/%s/orientation" % name)
00122 quaternion = tft.quaternion_from_euler(orientation[0], orientation[1], orientation[2])
00123 object_pose = Pose()
00124 object_pose.position.x = float(position[0])
00125 object_pose.position.y = float(position[1])
00126 object_pose.position.z = float(position[2])
00127 object_pose.orientation.x = quaternion[0]
00128 object_pose.orientation.y = quaternion[1]
00129 object_pose.orientation.z = quaternion[2]
00130 object_pose.orientation.w = quaternion[3]
00131
00132 try:
00133 file_localition = roslib.packages.get_pkg_dir('cob_gazebo_objects') + '/objects/' + model + '.' + model_type
00134 except:
00135 print "File not found: cob_gazebo_objects" + "/objects/" + model + "." + model_type
00136 continue
00137
00138
00139 if model_type == "urdf":
00140 srv_spawn_model = rospy.ServiceProxy('/gazebo/spawn_urdf_model', SpawnModel)
00141 file_xml = open(file_localition)
00142 xml_string=file_xml.read()
00143
00144 elif model_type == "urdf.xacro":
00145 p = os.popen("rosrun xacro xacro.py " + file_localition)
00146 xml_string = p.read()
00147 p.close()
00148 srv_spawn_model = rospy.ServiceProxy('/gazebo/spawn_urdf_model', SpawnModel)
00149
00150 elif model_type == "model":
00151 srv_spawn_model = rospy.ServiceProxy('/gazebo/spawn_gazebo_model', SpawnModel)
00152 file_xml = open(file_localition)
00153 xml_string=file_xml.read()
00154 else:
00155 rospy.logerr('Model type not know. model_type = ' + model_type)
00156 continue
00157
00158
00159
00160 srv_delete_model = rospy.ServiceProxy('gazebo/delete_model', DeleteModel)
00161 req = DeleteModelRequest()
00162 req.model_name = name
00163 exists = True
00164 try:
00165 rospy.wait_for_service('/gazebo/delete_model')
00166 res = srv_delete_model(name)
00167 except rospy.ServiceException, e:
00168 exists = False
00169 rospy.logdebug("Model %s does not exist in gazebo.", name)
00170
00171 if exists:
00172 rospy.loginfo("Model %s already exists in gazebo. Model will be updated.", name)
00173
00174
00175 req = SpawnModelRequest()
00176 req.model_name = name
00177 req.model_xml = xml_string
00178 req.initial_pose = object_pose
00179
00180 res = srv_spawn_model(req)
00181
00182
00183 if res.success == True:
00184 rospy.loginfo(res.status_message + " " + name)
00185 else:
00186 print "Error: model %s not spawn. error message = "% name + res.status_message
00187