00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018 import sys
00019
00020
00021 import rospy
00022 import os
00023 import copy
00024 import numpy
00025
00026 from optparse import OptionParser
00027
00028 from gazebo_msgs.srv import GetModelState, GetModelStateRequest, GetModelStateResponse
00029 from gazebo_msgs.msg import ModelState
00030 from geometry_msgs.msg import Pose
00031 import tf
00032 import math
00033
00034 _usage = """usage: %prog [options]
00035 %prog: Moves a model in gazebo
00036
00037 %prog -h
00038 Further help on options
00039 """
00040
00041 class move():
00042 def __init__(self):
00043 self.parse_options()
00044
00045 self.vel = float(self.options.velocity)
00046 self.name = self.options.name
00047 rospy.init_node('move' + self.name)
00048 self.models = self.options.stop_objects.split()
00049 rospy.wait_for_service('/gazebo/get_model_state')
00050 self.srv_get_model_state = rospy.ServiceProxy('/gazebo/get_model_state', GetModelState)
00051 self.pub = rospy.Publisher('/gazebo/set_model_state', ModelState, queue_size = 1)
00052 self.node_frequency = 100.0
00053 self.rate = rospy.Rate(self.node_frequency)
00054 self.road_block = False
00055 self.timeout_respawn = rospy.Duration(60)
00056
00057
00058 while not rospy.is_shutdown():
00059 rospy.sleep(1.0)
00060 res = self.get_model_state(self.name)
00061 if not res.success:
00062 continue
00063 else:
00064 success = True
00065 for model in self.models:
00066 res = self.get_model_state(model)
00067 if not res.success:
00068 success = False
00069 break
00070 if success:
00071 break
00072 rospy.logerr("Not all models available yet")
00073 rospy.loginfo("Ready to move object %s", self.name)
00074
00075 def get_model_state(self, model_name):
00076 req = GetModelStateRequest()
00077 res = GetModelStateResponse()
00078 req.model_name = model_name
00079 try:
00080 res = self.srv_get_model_state(req)
00081 except rospy.service.ServiceException:
00082 pass
00083 return res
00084
00085 def get_model_dist(self, x, y):
00086 model_dist = float('inf')
00087 for model in self.models:
00088 res = self.get_model_state(model)
00089 object_dist = math.sqrt(math.pow(res.pose.position.x-x,2) + math.pow(res.pose.position.y-y,2))
00090 model_dist = min(object_dist, model_dist)
00091 return model_dist
00092
00093 def move_on_line(self, start, goal):
00094 dx = goal[0] - start[0]
00095 dy = goal[1] - start[1]
00096 segment_length = math.sqrt(dx**2 + dy**2)
00097 segment_time = segment_length/self.vel
00098 yaw = math.atan2(dy, dx)
00099
00100 segment_step_count = int(segment_time*self.node_frequency)
00101
00102 if segment_step_count == 0:
00103 return
00104 segment_time = segment_length/self.vel/segment_step_count
00105 path = numpy.linspace(0, segment_length, segment_step_count)
00106
00107 idx = 0
00108 last_time_in_motion = rospy.Time.now()
00109 while idx < segment_step_count:
00110 step = path[idx]
00111
00112 step_x = start[0] + step * math.cos(yaw)
00113 step_y = start[1] + step * math.sin(yaw)
00114
00115
00116 model_dist = self.get_model_dist(step_x, step_y)
00117 if(model_dist <= float(self.options.stop_distance)):
00118 rospy.logdebug("Model too close to object. Stopping!")
00119 if (rospy.Time.now() - last_time_in_motion) > self.timeout_respawn:
00120 rospy.logdebug("Model move to last waypoint!")
00121 self.road_block = True
00122 return
00123 else:
00124 object_new_pose = Pose()
00125 object_new_pose.position.x = step_x
00126 object_new_pose.position.y = step_y
00127 quat = tf.transformations.quaternion_from_euler(0.0, 0.0, yaw)
00128 object_new_pose.orientation.x = quat[0]
00129 object_new_pose.orientation.y = quat[1]
00130 object_new_pose.orientation.z = quat[2]
00131 object_new_pose.orientation.w = quat[3]
00132
00133
00134 model_state = ModelState()
00135 model_state.model_name = self.name
00136 model_state.pose = object_new_pose
00137 model_state.reference_frame = 'world'
00138
00139
00140 self.pub.publish(model_state)
00141
00142 idx += 1
00143
00144
00145 last_time_in_motion = rospy.Time.now()
00146
00147
00148 self.rate.sleep()
00149
00150 def move_initialpose(self, initialpose):
00151 object_new_pose = Pose()
00152 object_new_pose.position.x = initialpose[0]
00153 object_new_pose.position.y = initialpose[1]
00154 object_new_pose.position.z = initialpose[2]
00155 quat = tf.transformations.quaternion_from_euler(initialpose[3], initialpose[4], initialpose[5])
00156 object_new_pose.orientation.x = quat[0]
00157 object_new_pose.orientation.y = quat[1]
00158 object_new_pose.orientation.z = quat[2]
00159 object_new_pose.orientation.w = quat[3]
00160
00161
00162 model_state = ModelState()
00163 model_state.model_name = self.name
00164 model_state.pose = object_new_pose
00165 model_state.reference_frame = 'world'
00166
00167
00168 self.pub.publish(model_state)
00169
00170 def move_polygon(self, polygon_in):
00171
00172 polygon = copy.deepcopy(polygon_in)
00173 polygon.append(polygon_in[0])
00174 while not rospy.is_shutdown():
00175 if len(polygon) <= 1:
00176
00177 polygon = copy.deepcopy(polygon_in)
00178 polygon.append(polygon_in[0])
00179
00180 start = polygon[0]
00181 goal = polygon[1]
00182
00183
00184 self.move_on_line(start, goal)
00185 if self.road_block:
00186 self.road_block = False
00187 continue
00188 polygon.pop(0)
00189
00190 def move_circle(self, center, radius):
00191
00192 yaw_step = math.asin(1.0/self.node_frequency*self.vel/radius)
00193 yaw = 0.0
00194 last_time_in_motion = rospy.Time.now()
00195 while not rospy.is_shutdown():
00196 if yaw >= 2*math.pi:
00197 rospy.loginfo("starting new round")
00198 yaw = 0.0
00199
00200 step_x = center[0] + radius * math.sin(yaw)
00201 step_y = center[1] + radius * math.cos(yaw)
00202
00203
00204 model_dist = self.get_model_dist(step_x, step_y)
00205 if(model_dist <= float(self.options.stop_distance)):
00206 rospy.logdebug("Model too close to object. Stopping!")
00207 if (rospy.Time.now() - last_time_in_motion) > self.timeout_respawn:
00208 rospy.logdebug("Model move to start waypont of the polygone!")
00209 yaw = 2*math.pi
00210 continue
00211 else:
00212 object_new_pose = Pose()
00213 object_new_pose.position.x = step_x
00214 object_new_pose.position.y = step_y
00215 quat = tf.transformations.quaternion_from_euler(0.0, 0.0, -yaw)
00216 object_new_pose.orientation.x = quat[0]
00217 object_new_pose.orientation.y = quat[1]
00218 object_new_pose.orientation.z = quat[2]
00219 object_new_pose.orientation.w = quat[3]
00220
00221
00222 model_state = ModelState()
00223 model_state.model_name = self.name
00224 model_state.pose = object_new_pose
00225 model_state.reference_frame = 'world'
00226
00227
00228 self.pub.publish(model_state)
00229
00230 yaw += yaw_step
00231
00232
00233 last_time_in_motion = rospy.Time.now()
00234
00235
00236 self.rate.sleep()
00237
00238 def parse_options(self):
00239 parser = OptionParser(usage=_usage, prog=os.path.basename(sys.argv[0]))
00240
00241 parser.add_option("-m", "--mode",
00242 dest="mode", choices=["initialpose", "polygon", "circle"], default=None,
00243 help="Mode to move model. Required.")
00244
00245 parser.add_option("-n", "--name",
00246 dest="name", metavar="STRING", default=None,
00247 help="Name of model to be moved. Required.")
00248
00249 parser.add_option("-i", "--initialpose",
00250 dest="initialpose", metavar="Initialpose [x, y, z, R, P, Y]", default=None,
00251 help="Cartesian Pose, only used for initialpose. Default: None")
00252
00253 parser.add_option("-v", "--velocity",
00254 dest="velocity", metavar="Float", default=0.5,
00255 help="Velocity for movement in [m/s]. Default: 0.5")
00256
00257 parser.add_option("-p", "--polygon",
00258 dest="polygon", metavar="List of points [[x1,y1],[x2,y2], ...]", default=None,
00259 help="List of points forming a polygon in [m], only used for polygon movement. Default: None")
00260
00261 parser.add_option("-c", "--center",
00262 dest="center", metavar="Point [x1,y1]", default=None,
00263 help="Center point, only used for circular movement. Default: None")
00264
00265 parser.add_option("-r", "--radius",
00266 dest="radius", metavar="Float", default=None,
00267 help="Radius, only used for circular movement. Default: None")
00268
00269 parser.add_option("-o", "--stop-objects",
00270 dest="stop_objects", metavar="List of objects 'object_1 object_2 ...'", default='',
00271 help="List of Model-Name of objects that are to be avoided. Default: ''")
00272
00273 parser.add_option("-d", "--stop-distance",
00274 dest="stop_distance", metavar="Float", default=2.0,
00275 help="Allowed distance to objects before stopping. Default: 2.0")
00276
00277 (self.options, args) = parser.parse_args()
00278
00279 if self.options.mode == None:
00280 parser.error("Please provide a valid mode, see -h option.")
00281 if self.options.name == None:
00282 parser.error("Please provide a valid model name, see -h option.")
00283
00284
00285 def run(self):
00286 if self.options.mode == "initialpose":
00287 if (self.options.initialpose == None):
00288 parser.error("Please provide a valid initialpose, see -h option. initialpose = " + str(self.options.initialpose))
00289 self.move_initialpose(eval(self.options.initialpose))
00290 if self.options.mode == "polygon":
00291 if (self.options.polygon == None) or (type(eval(self.options.polygon)) is not list):
00292 parser.error("Please provide a valid polygon, see -h option. polygon = " + str(self.options.polygon))
00293 self.move_polygon(eval(self.options.polygon))
00294 if self.options.mode == "circle":
00295 if self.options.radius == None:
00296 parser.error("Please provide a valid radius. radius = " + str(self.options.radius))
00297 if self.options.center == None:
00298 parser.error("Please provide a valid center. center = " + str(self.options.center))
00299 self.move_circle(eval(self.options.center),float(self.options.radius))
00300
00301
00302 if __name__ == "__main__":
00303 try:
00304 m = move()
00305 m.run()
00306 except rospy.ROSInterruptException:
00307 pass