Go to the documentation of this file.00001 
00002 
00003 import roslib
00004 roslib.load_manifest('explore_hrl')
00005 import rospy
00006 
00007 import actionlib
00008 import explore_hrl.msg
00009 
00010 def explore_client( radius ):
00011     client = actionlib.SimpleActionClient('explore', explore_hrl.msg.ExploreAction)
00012 
00013     
00014     
00015     client.wait_for_server()
00016 
00017     
00018     goal = explore_hrl.msg.ExploreGoal( radius = radius )
00019 
00020     
00021     client.send_goal(goal)
00022 
00023     r = rospy.Rate( 1 )
00024     t0 = rospy.Time.now().to_time()
00025     
00026     
00027     
00028 
00029     
00030     client.wait_for_result()
00031 
00032     
00033     
00034     return client.get_state()
00035 
00036 if __name__ == '__main__':
00037     import optparse
00038     p = optparse.OptionParser()
00039     p.add_option('-r', action='store', type='float', dest='radius', help='Sensing radius', default=2.0)
00040     opt, args = p.parse_args()
00041     
00042     try:
00043         
00044         
00045         rospy.init_node('explore_client_py')
00046         result = explore_client( opt.radius )
00047         if result == actionlib.GoalStatus.SUCCEEDED:
00048             print 'SUCCEEDED'
00049         else:
00050             print 'FAILED'
00051     except rospy.ROSInterruptException:
00052         print "program interrupted before completion"