00001
00002
00003 import roslib
00004 roslib.load_manifest('room_explore')
00005 import rospy
00006
00007 import tf
00008 from threading import Thread
00009 import actionlib
00010
00011 from move_base_msgs.msg import MoveBaseGoal, MoveBaseAction
00012 from visualization_msgs.msg import MarkerArray
00013 from visualization_msgs.msg import Marker
00014 from geometry_msgs.msg import Vector3, PoseStamped, Quaternion
00015 from std_msgs.msg import ColorRGBA
00016
00017 from explore_hrl.msg import ExploreAction, ExploreResult, ExploreGoal
00018
00019 import yaml
00020 import numpy as np, math
00021
00022 room = '/home/travis/svn/gt-ros-pkg/hrl/room_explore/rooms/rooms.yaml'
00023
00024 def retfalse():
00025 return False
00026
00027 class TFthread( Thread ):
00028 def __init__( self, df ):
00029 Thread.__init__( self )
00030 try:
00031 rospy.init_node( 'TFthread' )
00032 except:
00033 pass
00034 self.df = df
00035 self.bc = tf.TransformBroadcaster()
00036 self.should_run = True
00037 self.start()
00038
00039 def publish_transform( self ):
00040 for room in self.df.keys():
00041 self.bc.sendTransform( ( self.df[room]['position']['x'],
00042 self.df[room]['position']['y'],
00043 self.df[room]['position']['z'] ),
00044 ( self.df[room]['orientation']['x'],
00045 self.df[room]['orientation']['y'],
00046 self.df[room]['orientation']['z'],
00047 self.df[room]['orientation']['w'] ),
00048 rospy.Time.now(),
00049 room,
00050 'map' )
00051
00052 def run( self ):
00053 rospy.logout( 'TFthread: Starting ' )
00054 r = rospy.Rate( 10 )
00055 while self.should_run and not rospy.is_shutdown():
00056 self.publish_transform()
00057 try:
00058 r.sleep()
00059 except:
00060 pass
00061 rospy.logout( 'TFthread: Starting ')
00062
00063 def stop( self ):
00064
00065 self.should_run = False
00066 self.join(5)
00067 if (self.isAlive()):
00068 raise RuntimeError('TFthread: Unable to stop thread ' )
00069
00070
00071
00072
00073
00074
00075
00076
00077
00078
00079 def standard_rad(t):
00080 if t > 0:
00081 return ((t + np.pi) % (np.pi * 2)) - np.pi
00082 else:
00083 return ((t - np.pi) % (np.pi * -2)) + np.pi
00084
00085
00086 class RoomExplore( Thread ):
00087 def __init__( self, df, room, start_rad = 1.5 ):
00088 Thread.__init__( self )
00089 try:
00090 rospy.init_node( 'RoomExplore' )
00091 except:
00092 pass
00093 self.should_run = True
00094
00095 self.frame = '/' + room
00096
00097 self.height = df[room]['height']
00098 self.width = df[room]['width']
00099
00100 self.listener = tf.TransformListener()
00101 self.listener.waitForTransform( '/base_link', '/map', rospy.Time(0), timeout = rospy.Duration(100))
00102
00103 self.setup_poses( radius = start_rad )
00104
00105 self.pub = rospy.Publisher( 'visarr', Marker )
00106 self._as = actionlib.SimpleActionServer( '/explore', ExploreAction, execute_cb = self.action_request )
00107 self._as.start()
00108 rospy.logout('Action should be started.')
00109 self.start()
00110
00111 def action_request( self, goal ):
00112 rospy.logout( 'room_explore: action_request received for radius: \'%2.2f\'' % goal.radius )
00113
00114 def preempt_func():
00115
00116 check = self._as.is_preempt_requested()
00117 if check:
00118 rospy.logout( 'room_explore: action_request preempted!' )
00119 return check
00120
00121 rv = self.begin_explore( goal.radius, preempt_func = preempt_func )
00122 rospy.logout( 'room_explore: action_request received result %d' % int(rv) )
00123
00124 if rv == True:
00125 self._as.set_succeeded( ExploreResult() )
00126
00127
00128 def begin_explore( self, radius, preempt_func = retfalse ):
00129 client = actionlib.SimpleActionClient( 'move_base', MoveBaseAction )
00130 rospy.logout( 'Waiting for move_base server' )
00131 client.wait_for_server()
00132
00133 rospy.logout( 'room_explore: setting radius' )
00134 all_goals = self.setup_poses( radius )
00135 for goal in all_goals:
00136
00137 goal.target_pose.header.stamp = rospy.Time.now()
00138
00139 client.send_goal( goal )
00140
00141 time_last_moving = rospy.Time.now()
00142 goal_time = rospy.Time.now()
00143
00144 new_pose = self.current_robot_position()
00145 ref_pose = self.current_robot_position()
00146
00147 r = rospy.Rate( 5 )
00148 while not rospy.is_shutdown():
00149 state = client.get_state()
00150 states = { 0: 'WAITING FOR GOAL ACK',
00151 1: 'PENDING',
00152 2: 'ACTIVE',
00153 3: 'WAITING FOR RESULT',
00154 4: 'WAITING FOR CANCEL ACK',
00155 5: 'RECALLING',
00156 6: 'PREEMPTING',
00157 7: 'DONE' }
00158
00159
00160
00161
00162 if state == 7 or state == 3:
00163 rospy.logout( 'room_explore: client no longer active' )
00164 print 'State: ', state, ' ', states[state]
00165 time_last_moving = rospy.Time.now()
00166 break
00167
00168 if preempt_func():
00169 rospy.logout( 'room_explore: preempted at a higher level.' )
00170 time_last_moving = rospy.Time.now()
00171 break
00172
00173 new_pose = self.current_robot_position()
00174 dx = new_pose[0] - ref_pose[0]
00175 dy = new_pose[1] - ref_pose[1]
00176 da = new_pose[-1] - ref_pose[-1]
00177
00178 if dx*dx + dy*dy > 0.02 or da*da > math.radians( 5 ):
00179 time_last_moving = rospy.Time.now()
00180 ref_pose = self.current_robot_position()
00181 rospy.logout('WE ARE MOVING')
00182
00183 if rospy.Time.now() - time_last_moving > rospy.Duration( 8 ):
00184 rospy.logout( 'We do not appear to have moved. Aborting current goal.' )
00185 client.cancel_all_goals()
00186 time_last_moving = rospy.Time.now()
00187 break
00188
00189 if rospy.Time.now() - goal_time > rospy.Duration( 30 ):
00190 rospy.logout( 'Goal not achieved after 30 seconds. Aborting.' )
00191 client.cancel_all_goals()
00192 time_last_moving = rospy.Time.now()
00193 break
00194
00195 r.sleep()
00196
00197 client.cancel_all_goals()
00198
00199 if preempt_func():
00200 break
00201
00202 return True
00203
00204
00205 def current_robot_position( self ):
00206 ps = PoseStamped()
00207 ps.header.stamp = rospy.Time(0)
00208 ps.header.frame_id = '/base_link'
00209 ps.pose.orientation.w = 1.0
00210
00211 try:
00212 ps_map = self.listener.transformPose( '/map', ps )
00213 except:
00214 rospy.logout( 'room_explore: Transform failed' )
00215 ps_map = PoseStamped()
00216 ps_map.header.stamp = rospy.Time.now()
00217 ps_map.header.frame_id = '/map'
00218 ps_map.pose.orientation = new_quat
00219
00220 roll, pitch, yaw = tf.transformations.euler_from_quaternion(( ps_map.pose.orientation.x,
00221 ps_map.pose.orientation.y,
00222 ps_map.pose.orientation.z,
00223 ps_map.pose.orientation.w ))
00224
00225 rv = [ ps_map.pose.position.x,
00226 ps_map.pose.position.y,
00227 ps_map.pose.position.z,
00228 roll,
00229 pitch,
00230 yaw ]
00231
00232
00233 return rv
00234
00235
00236 def setup_poses( self, radius ):
00237 self.radius = radius
00238 xdir = np.arange( self.radius / 2.0, self.height + self.radius / 2.0, self.radius )
00239 ydir = np.arange( self.radius / 2.0, self.width + self.radius / 2.0, self.radius )
00240
00241 move_dir = 0.0
00242 self.poses = []
00243 mod = 0
00244 for y in ydir:
00245 if mod == 0:
00246 xord = xdir
00247 else:
00248 xord = xdir[::-1]
00249
00250 for x in xord:
00251 goal = MoveBaseGoal()
00252 goal.target_pose.header.frame_id = self.frame
00253 goal.target_pose.header.stamp = rospy.Time.now()
00254 goal.target_pose.pose.position.x = x
00255 goal.target_pose.pose.position.y = y
00256 quat = tf.transformations.quaternion_from_euler( 0.0, 0.0, move_dir )
00257 goal.target_pose.pose.orientation.x = quat[0]
00258 goal.target_pose.pose.orientation.y = quat[1]
00259 goal.target_pose.pose.orientation.z = quat[2]
00260 goal.target_pose.pose.orientation.w = quat[3]
00261
00262 self.poses.append( goal )
00263 move_dir = standard_rad( move_dir + np.pi )
00264 mod = ( mod + 1 ) % 2
00265 return self.poses
00266
00267
00268 def run( self ):
00269 rospy.logout( 'RoomExplore: Starting ' )
00270 r = rospy.Rate( 2 )
00271 while self.should_run and not rospy.is_shutdown():
00272 self.publish_markers()
00273 try:
00274 r.sleep()
00275 except:
00276 pass
00277 rospy.logout( 'RoomExplore: Starting ' )
00278
00279 def stop( self ):
00280
00281 self.should_run = False
00282 self.join(5)
00283 if (self.isAlive()):
00284 raise RuntimeError('RoomExplore: Unable to stop thread ' )
00285
00286
00287 def publish_markers( self ):
00288 for i,g in enumerate(self.poses):
00289 m = Marker()
00290 m.ns = 'sample_positions'
00291 m.id = i
00292 m.action = m.ADD
00293 m.type = m.ARROW
00294 m.header.frame_id = self.frame
00295 m.header.stamp = rospy.Time.now()
00296 m.scale = Vector3( 0.15, 1.0, 1.0 )
00297 m.color = ColorRGBA( 0.2, 1.0, 0.2, 0.7 )
00298 m.pose = g.target_pose.pose
00299
00300 self.pub.publish( m )
00301
00302 def goals( self ):
00303 return self.poses
00304
00305
00306
00307
00308
00309
00310
00311 if __name__ == '__main__':
00312 f = open( room )
00313 dat = yaml.load( f )
00314 f.close()
00315
00316 TFthread( dat )
00317
00318 re = RoomExplore( dat, 'hrl', 0.8 )
00319
00320
00321
00322
00323
00324
00325
00326
00327
00328
00329
00330
00331
00332
00333 rospy.spin()
00334
00335