$search
00001 #!/usr/bin/python 00002 # Software License Agreement (BSD License) 00003 # 00004 # Copyright (c) 2008, Willow Garage, Inc. 00005 # All rights reserved. 00006 # 00007 # Redistribution and use in source and binary forms, with or without 00008 # modification, are permitted provided that the following conditions 00009 # are met: 00010 # 00011 # * Redistributions of source code must retain the above copyright 00012 # notice, this list of conditions and the following disclaimer. 00013 # * Redistributions in binary form must reproduce the above 00014 # copyright notice, this list of conditions and the following 00015 # disclaimer in the documentation and/or other materials provided 00016 # with the distribution. 00017 # * Neither the name of the Willow Garage nor the names of its 00018 # contributors may be used to endorse or promote products derived 00019 # from this software without specific prior written permission. 00020 # 00021 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 # POSSIBILITY OF SUCH DAMAGE. 00033 # 00034 00035 # Author: Wim Meeussen 00036 00037 00038 00039 import roslib; roslib.load_manifest('continuous_ops_executive') 00040 import rospy 00041 import actionlib 00042 import smach 00043 import smach_ros 00044 from pr2_msgs.msg import PowerState 00045 from std_msgs.msg import String, Float64, UInt8 00046 from actionlib_msgs.msg import GoalStatus 00047 from pr2_plugs_msgs.msg import RechargeAction, RechargeGoal, RechargeCommand 00048 from continuous_ops_msgs.msg import TaskAction, TaskGoal, ChargeStatus 00049 from continuous_ops_msgs.srv import * 00050 from random import choice 00051 from threading import Thread 00052 00053 # Define Battery Monitor state 00054 class HighBatteryMonitor(smach.State): 00055 def __init__(self): 00056 smach.State.__init__(self, outcomes=['stuffed', 'not_plugged_in', 'preempted']) 00057 self._charge_data = ChargeStatus() 00058 self.sub = rospy.Subscriber('charge_status', ChargeStatus, self.charge_cb) 00059 self.srv = rospy.ServiceProxy('task_manager/get_scheduled_tasks', GetTaskList) 00060 00061 def execute(self, userdata): 00062 rospy.loginfo('Monitoring battery level and task schedule') 00063 while not rospy.is_shutdown(): 00064 # we're still using battery power 00065 if self._charge_data.charge_status == ChargeStatus.UNPLUGGED: 00066 rospy.logerr('Robot is not plugged in correctly!') 00067 return 'not_plugged_in' 00068 00069 # low battery level 00070 task_list = self.srv().tasks 00071 if (self._charge_data.battery_status == ChargeStatus.STUFFED) and len(task_list) > 0: 00072 return 'stuffed' 00073 # preemption 00074 if self.preempt_requested(): 00075 self.service_preempt() 00076 return 'preempted' 00077 rospy.sleep(0.1) 00078 00079 def charge_cb(self, msg): 00080 self._charge_data = msg 00081 00082 # Montior state for low battery and task schedule 00083 class LowBatteryMonitor(smach.State): 00084 def __init__(self): 00085 smach.State.__init__(self, outcomes=['bored', 'hungry','preempted']) 00086 self._charge_data = ChargeStatus() 00087 self.sub = rospy.Subscriber('charge_status', ChargeStatus, self.charge_cb) 00088 self.srv = rospy.ServiceProxy('task_manager/get_scheduled_tasks', GetTaskList) 00089 00090 def execute(self, userdata): 00091 rospy.loginfo('Monitoring battery level and task schedule') 00092 while not rospy.is_shutdown(): 00093 # low battery level 00094 if self._charge_data.battery_status == ChargeStatus.HUNGRY: 00095 rospy.loginfo("hungry") 00096 return 'hungry' 00097 # no tasks and medium battery level 00098 resp = self.srv() 00099 if (not self._charge_data.battery_status == ChargeStatus.HUNGRY) and (self._charge_data.charge_status == ChargeStatus.UNPLUGGED) and len(resp.tasks) == 0: 00100 rospy.loginfo("Continuous ops bored") 00101 return 'bored' 00102 # preemption 00103 if self.preempt_requested(): 00104 self.service_preempt() 00105 rospy.loginfo("Continuous ops was preempted") 00106 return 'preempted' 00107 rospy.sleep(0.1) 00108 00109 def charge_cb(self, msg): 00110 self._charge_data = msg 00111 00112 00113 00114 # Launch a task 00115 class TaskLaunchState(smach.State): 00116 def __init__(self): 00117 smach.State.__init__(self, 00118 outcomes=['succeeded', 'aborted', 'preempted'], 00119 output_keys=['task']) 00120 self.list_srv = rospy.ServiceProxy('task_manager/get_scheduled_tasks', GetTaskList) 00121 self.start_srv = rospy.ServiceProxy('task_manager/start_task', ChangeTask) 00122 00123 00124 def execute(self, userdata): 00125 # service the first available task 00126 task_list = self.list_srv().tasks 00127 if self.preempt_requested(): 00128 self.service_preempt() 00129 return 'preempted' 00130 00131 if len(task_list) == 0: 00132 rospy.logerr("No scheduled tasks to run") 00133 rospy.sleep(5) 00134 return 'aborted' 00135 00136 task_list = self.start_srv(ChangeTaskRequest(task_list[0].run_id)).tasks 00137 if len(task_list) == 0: 00138 rospy.logerr("No scheduled tasks to run") 00139 rospy.sleep(5) 00140 return 'aborted' 00141 00142 if task_list[0].state == 'Running': 00143 userdata.task = task_list[0] 00144 return 'succeeded' 00145 return 'aborted' 00146 00147 00148 00149 # Kill a task 00150 class TaskKillState(smach.State): 00151 def __init__(self): 00152 smach.State.__init__(self, 00153 outcomes=['succeeded', 'preempted'], 00154 input_keys=['task']) 00155 self.stop_srv = rospy.ServiceProxy('task_manager/stop_task', ChangeTask) 00156 self.remove_srv = rospy.ServiceProxy('task_manager/remove_task', ChangeTask) 00157 00158 def execute(self, userdata): 00159 self.stop_srv(ChangeTaskRequest(userdata.task.run_id)) 00160 00161 if not self.preempt_requested(): 00162 self.remove_srv(ChangeTaskRequest(userdata.task.run_id)) 00163 return 'succeeded' 00164 else: 00165 self.service_preempt() 00166 return 'preempted' 00167 00168 00169 00170 00171 00172 # Run the task action 00173 class TaskRunState(smach.State): 00174 def __init__(self): 00175 smach.State.__init__(self, 00176 outcomes=['succeeded', 'aborted', 'preempted'], 00177 input_keys=['task'], 00178 output_keys=['task']) 00179 self.connect_timeout = rospy.Duration(30) 00180 self.preempt_timeout = rospy.Duration(30) 00181 self.succeeded = [] 00182 self.aborted = [] 00183 self.preempted = [] 00184 self.srv = rospy.Service('continuous_ops_executive/cancel_running_task', ChangeTask, self.cancel_srv) 00185 00186 def execute(self, userdata): 00187 self.cancel_run_id = '' 00188 print "service should be up" 00189 00190 # wait for action client to connect with server 00191 rospy.loginfo('Connecting to action server %s'%userdata.task.action_ns) 00192 self.ac = actionlib.SimpleActionClient(userdata.task.action_ns, TaskAction) 00193 start_time = rospy.Time.now() 00194 while not rospy.is_shutdown() and not self.ac.wait_for_server(rospy.Duration(0.2)): 00195 if self.cancel_run_id == userdata.task.run_id: 00196 self.cancel_run_id = '' 00197 self.aborted.append(userdata.task.name) 00198 rospy.logerr('Canceling task before it is connected to action server') 00199 return 'aborted' 00200 if self.preempt_requested(): 00201 self.preempted.append(userdata.task.name) 00202 return 'preempted' 00203 if rospy.Time.now() > start_time + self.connect_timeout: 00204 self.aborted.append(userdata.task.name) 00205 rospy.logerr('Timed out waiting for action server of task') 00206 return 'aborted' 00207 00208 # run the task 00209 rospy.loginfo('Sending goal to action server %s'%userdata.task.action_ns) 00210 self.preempting = False 00211 self.ac.send_goal(TaskGoal()) 00212 start_time = rospy.Time.now() 00213 while not rospy.is_shutdown(): 00214 # reasons to preempt 00215 if self.cancel_run_id == userdata.task.run_id: 00216 self.preempt_task('Current task canceled from external source') 00217 if self.preempt_requested(): 00218 self.preempt_task('Current task being preempted by state machine') 00219 if userdata.task.timeout != rospy.Duration(0) and rospy.Time.now() > start_time + userdata.task.timeout: 00220 self.preempt_task('Current task exceeded its allocated time slot') 00221 00222 # reasons to abort 00223 if self.preempting and rospy.Time.now() > self.preempting_start + self.preempt_timeout: 00224 rospy.logerr('Task did not preempt within timeout. Aborting') 00225 return 'aborted' 00226 00227 # Check actual state 00228 state = self.ac.get_state() 00229 if state == GoalStatus.SUCCEEDED: 00230 self.succeeded.append(userdata.task.name) 00231 rospy.loginfo('Task succeeded') 00232 return 'succeeded' 00233 elif state == GoalStatus.PREEMPTED: 00234 self.preempted.append(userdata.task.name) 00235 rospy.logwarn('Task preempted') 00236 return 'preempted' 00237 elif state in [GoalStatus.RECALLED, 00238 GoalStatus.REJECTED, 00239 GoalStatus.ABORTED, 00240 GoalStatus.LOST]: 00241 self.aborted.append(userdata.task.name) 00242 rospy.logerr('Task aborted') 00243 return 'aborted' 00244 rospy.sleep(0.2) 00245 00246 def preempt_task(self, msg): 00247 if not self.preempting: 00248 self.ac.cancel_all_goals() 00249 self.preempting = True 00250 self.preempting_start = rospy.Time.now() 00251 rospy.logwarn('%s'%msg) 00252 00253 00254 def cancel_srv(self, req): 00255 self.cancel_run_id = req.run_id 00256 return ChangeTaskResponse() 00257 00258 00259 00260 00261 class TimeLogger(Thread): 00262 def __init__(self): 00263 Thread.__init__(self) 00264 self.start_time = rospy.Time.now() 00265 00266 def run(self): 00267 print 'Running' 00268 pub = rospy.Publisher('continuous_ops_duration', Float64) 00269 while not rospy.is_shutdown(): 00270 rospy.sleep(2.0) 00271 pub.publish((rospy.Time.now() - self.start_time).to_sec()) 00272 00273 00274 def main(): 00275 rospy.init_node('continuous_ops_executive') 00276 00277 time_logger = TimeLogger() 00278 time_logger.start() 00279 00280 # wait for task manager 00281 rospy.loginfo('Detecting task manager...') 00282 rospy.wait_for_service('task_manager/get_scheduled_tasks') 00283 rospy.wait_for_service('task_manager/start_task') 00284 rospy.wait_for_service('task_manager/stop_task') 00285 rospy.wait_for_service('task_manager/remove_task') 00286 rospy.loginfo('Connected to task manager') 00287 00288 # Create the top level SMACH state machine 00289 sm_top = smach.StateMachine(outcomes=['aborted', 'preempted']) 00290 with sm_top: 00291 00292 # ----------------- 00293 # Task with monitor 00294 # ----------------- 00295 def child_term_cb(outcome_map): 00296 # if any of the states exit for another reason, preempt the other state 00297 rospy.loginfo('One concurrent state finished, preempting other state') 00298 return True 00299 def out_cb(outcome_map): 00300 if outcome_map['LOW_BATTERY_MONITOR'] == 'hungry': 00301 return 'hungry' 00302 if outcome_map['LOW_BATTERY_MONITOR'] == 'bored': 00303 return 'bored' 00304 return 'continue' 00305 sm_task_monitor = smach.Concurrence(outcomes=['continue', 'hungry', 'bored'], 00306 default_outcome='continue', 00307 child_termination_cb = child_term_cb, 00308 outcome_cb = out_cb) 00309 with sm_task_monitor: 00310 sm_task = smach.StateMachine(outcomes=['succeeded', 'aborted', 'preempted']) 00311 with sm_task: 00312 # Launch a task 00313 smach.StateMachine.add('LAUNCH_TASK', TaskLaunchState(), 00314 transitions={'succeeded':'RUN_TASK', 00315 'aborted':'LAUNCH_TASK', 00316 'preempted':'preempted'}) 00317 # Run a task 00318 smach.StateMachine.add('RUN_TASK', TaskRunState(), 00319 transitions={'succeeded':'KILL_TASK', 00320 'aborted':'KILL_TASK', 00321 'preempted':'KILL_TASK'}) 00322 # Kill a task 00323 smach.StateMachine.add('KILL_TASK', TaskKillState(), 00324 transitions={'succeeded':'LAUNCH_TASK', 00325 'preempted':'preempted'}) 00326 00327 # Tasks to execute 00328 smach.Concurrence.add('TASK', sm_task) 00329 00330 # Low battery monitor 00331 smach.Concurrence.add('LOW_BATTERY_MONITOR', LowBatteryMonitor()) 00332 00333 # Add to top level sm 00334 smach.StateMachine.add('TASK_WITH_MONITOR', sm_task_monitor, 00335 transitions={'continue':'TASK_WITH_MONITOR', 00336 'bored':'RECHARGE', 00337 'hungry':'RECHARGE'}) 00338 00339 00340 00341 # -------- 00342 # Recharge 00343 # -------- 00344 sm_recharge = smach.StateMachine(outcomes=['aborted', 'preempted', 'stuffed']) 00345 00346 with sm_recharge: 00347 # choose random recharging location 00348 def location_cb(userdata, goal): 00349 goal.command.plug_id = choice(['wim', 'james']) 00350 rospy.loginfo("Recharging at location %s"%goal.command.plug_id) 00351 return goal 00352 plugin = RechargeGoal(RechargeCommand(RechargeCommand.PLUG_IN, '')) 00353 smach.StateMachine.add('PLUG_IN', smach_ros.SimpleActionState('recharge', 00354 RechargeAction, 00355 goal=plugin, 00356 goal_cb=location_cb), 00357 transitions={'aborted':'PLUG_IN', 00358 'succeeded':'HIGH_BATTERY_MONITOR', 00359 'preempted':'preempted'}) 00360 00361 # wait until battery is charged 00362 smach.StateMachine.add('HIGH_BATTERY_MONITOR', HighBatteryMonitor(), 00363 transitions={'preempted':'preempted', 00364 'stuffed':'UNPLUG', 00365 'not_plugged_in':'UNPLUG_RECOVER'}) 00366 00367 # unplug 00368 unplug = RechargeGoal(RechargeCommand(RechargeCommand.UNPLUG, '')) 00369 smach.StateMachine.add('UNPLUG', smach_ros.SimpleActionState('recharge', 00370 RechargeAction, 00371 goal=unplug), 00372 transitions={'succeeded':'stuffed', 00373 'aborted':'UNPLUG', 00374 'preempted':'preempted'}) 00375 00376 # unplug 00377 unplug = RechargeGoal(RechargeCommand(RechargeCommand.UNPLUG, '')) 00378 smach.StateMachine.add('UNPLUG_RECOVER', smach_ros.SimpleActionState('recharge', 00379 RechargeAction, 00380 goal=unplug), 00381 transitions={'succeeded':'PLUG_IN', 00382 'aborted':'UNPLUG_RECOVER', 00383 'preempted':'preempted'}) 00384 00385 smach.StateMachine.add('RECHARGE', sm_recharge, 00386 transitions={'aborted':'aborted', 00387 'stuffed':'TASK_WITH_MONITOR'}) 00388 00389 00390 # Create and start the introspection server 00391 sis = smach_ros.IntrospectionServer('continuous_ops_executive_server', sm_top, '/CONTINUOUS_OPERATION_EXECUTIVE') 00392 sis.start() 00393 00394 # Execute SMACH plan 00395 rospy.sleep(4) 00396 outcome = sm_top.execute() 00397 00398 # Wait for ctrl-c to stop the application 00399 rospy.spin() 00400 sis.stop() 00401 00402 00403 if __name__ == '__main__': 00404 main()