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 import sys
00019 import os
00020
00021 import roslib
00022 import rospy
00023 import copy
00024 import math
00025
00026 from gazebo_msgs.srv import SpawnModel, SpawnModelRequest, DeleteModel, DeleteModelRequest, GetWorldProperties
00027 from geometry_msgs.msg import Pose
00028 import tf.transformations as tft
00029
00030 parents = {}
00031 compound_keys={}
00032
00033 def get_flat_dict(objects, parent_name):
00034 """expands all objects to a flat dictionary"""
00035 flat_objects = {}
00036 for key, value in objects.iteritems():
00037
00038
00039 if(parent_name!=None):
00040
00041 if('parent_name' not in parents):
00042 parents[key] = parent_name
00043
00044 compound_keys[parent_name] = parent_name
00045
00046 compound_keys[key] = key+'_'+compound_keys[parent_name]
00047
00048 else:
00049 compound_keys[key] = key
00050
00051 if "children" in value:
00052
00053 tmp_value = copy.deepcopy(value)
00054 to_process = tmp_value["children"]
00055
00056
00057 for child_key, child_value in tmp_value["children"].iteritems():
00058 yaw = objects[key]["orientation"][2]
00059 x = objects[key]["position"][0] + math.cos(yaw) * child_value["position"][0] - math.sin(yaw) * child_value["position"][1]
00060 y = objects[key]["position"][1] + math.sin(yaw) * child_value["position"][0] + math.cos(yaw) * child_value["position"][1]
00061 child_value["position"][0] = x
00062 child_value["position"][1] = y
00063 child_value["position"][2] = objects[key]["position"][2] + child_value["position"][2]
00064 child_value["orientation"][2] = yaw + child_value["orientation"][2]
00065 del tmp_value["children"]
00066 flat_objects.update({compound_keys[key]:tmp_value})
00067
00068 flat_objects.update(get_flat_dict(to_process, compound_keys[key]))
00069
00070 else:
00071
00072 flat_objects.update({compound_keys[key]:value})
00073
00074 return flat_objects
00075
00076 if __name__ == "__main__":
00077 if len(sys.argv) < 2:
00078 print '[spawn_object.py] Please specify the names of the objects to be loaded'
00079 sys.exit()
00080
00081 rospy.init_node("object_spawner")
00082
00083
00084 if not rospy.has_param("/objects"):
00085 rospy.logerr("No objects uploaded to /objects")
00086 sys.exit()
00087 objects = rospy.get_param("/objects")
00088 flat_objects = get_flat_dict(objects,None)
00089
00090
00091 if rospy.has_param("/object_groups"):
00092 groups = rospy.get_param("/object_groups")
00093 else:
00094 groups = {}
00095 rospy.loginfo('No object-groups uploaded to /object_groups')
00096
00097
00098 if "all" in sys.argv:
00099 objects = flat_objects
00100 elif not set(groups.keys()).isdisjoint(sys.argv):
00101
00102 found_groups = set(groups.keys()) & set(sys.argv)
00103
00104 object_names = [groups[k] for k in found_groups]
00105
00106 object_names = [item for sublist in object_names for item in sublist]
00107
00108 objects = {}
00109 for object_name in object_names:
00110 if object_name in flat_objects.keys():
00111 objects.update({object_name:flat_objects[object_name]})
00112 elif sys.argv[1] not in flat_objects.keys():
00113 rospy.logerr("Object %s not found", sys.argv[1])
00114 sys.exit()
00115 else:
00116 objects = {sys.argv[1]:flat_objects[sys.argv[1]]}
00117
00118 rospy.loginfo("Trying to spawn %s", objects.keys())
00119
00120
00121
00122 try:
00123 rospy.wait_for_service('/gazebo/get_world_properties', 30)
00124 except rospy.exceptions.ROSException:
00125 rospy.logerr("Service /gazebo/get_world_properties not available.")
00126 sys.exit()
00127
00128 srv_get_world_properties = rospy.ServiceProxy('/gazebo/get_world_properties', GetWorldProperties)
00129
00130 try:
00131 world_properties = srv_get_world_properties()
00132 except rospy.ServiceException as exc:
00133 rospy.logerr("Service did not process request: " + str(exc))
00134
00135 if world_properties.success:
00136 existing_models = world_properties.model_names
00137 else:
00138 existing_models = []
00139
00140
00141 for key, value in objects.iteritems():
00142
00143 if not "model" in value:
00144 rospy.logerr("No model for " + key + " found.")
00145 continue
00146 model_string = value["model"]
00147 model_type = value["model_type"]
00148
00149
00150 if not "position" in value:
00151 rospy.logerr("No position for " + key + " found.")
00152 continue
00153 position = value["position"]
00154
00155
00156 if not "orientation" in value:
00157 rospy.logerr("No orientation for " + key + " found.")
00158 continue
00159
00160 orientation = value["orientation"]
00161 quaternion = tft.quaternion_from_euler(orientation[0], orientation[1], orientation[2])
00162
00163
00164 object_pose = Pose()
00165 object_pose.position.x = float(position[0])
00166 object_pose.position.y = float(position[1])
00167 object_pose.position.z = float(position[2])
00168 object_pose.orientation.x = quaternion[0]
00169 object_pose.orientation.y = quaternion[1]
00170 object_pose.orientation.z = quaternion[2]
00171 object_pose.orientation.w = quaternion[3]
00172
00173
00174 try:
00175 file_location = roslib.packages.get_pkg_dir('cob_gazebo_objects') + '/objects/' + model_string+ '.' + model_type
00176 except roslib.packages.InvalidROSPkgException:
00177 rospy.logerr("No model package found for " + key + ": " + cob_gazebo_objects + " does not exist in ROS_PACKAGE_PATH")
00178 continue
00179
00180
00181 if model_type == "urdf.xacro":
00182 try:
00183 f = os.popen("rosrun xacro xacro --inorder " + file_location)
00184 except:
00185 rospy.logerr("No xacro file found for " + key + " at " + file_location)
00186 continue
00187 model_type = "urdf"
00188 elif model_type in ['urdf', 'sdf', 'model']:
00189 try:
00190 f = open(file_location)
00191 except:
00192 rospy.logerr("No model file found for " + key + " at " + file_location)
00193 continue
00194 else:
00195 rospy.logerr('Model type not known. model_type = ' + model_type)
00196 continue
00197
00198
00199 xml_string = f.read()
00200 f.close()
00201
00202
00203 try:
00204 rospy.wait_for_service('/gazebo/spawn_'+model_type+'_model',30)
00205 except rospy.exceptions.ROSException:
00206 rospy.logerr("Service /gazebo/spawn_"+model_type+"_model not available.")
00207 sys.exit()
00208 srv_spawn_model = rospy.ServiceProxy('/gazebo/spawn_'+model_type+'_model', SpawnModel)
00209
00210
00211 if key in existing_models:
00212 srv_delete_model = rospy.ServiceProxy('gazebo/delete_model', DeleteModel)
00213 try:
00214 res = srv_delete_model(key)
00215 except rospy.ServiceException, e:
00216 rospy.logdebug("Error while trying to call Service /gazebo/get_world_properties.")
00217 rospy.loginfo("Model %s already exists in gazebo. Model will be deleted and added again.", key)
00218
00219
00220 req = SpawnModelRequest()
00221 req.model_name = key
00222 req.model_xml = xml_string
00223 req.initial_pose = object_pose
00224
00225 try:
00226 res = srv_spawn_model(req)
00227 except rospy.service.ServiceException:
00228 break
00229
00230
00231 if res.success == True:
00232 rospy.loginfo(res.status_message + " " + key)
00233 else:
00234 rospy.logerr("Error: model %s not spawn. error message = "% key + res.status_message)
00235