schedule_status.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 import rospy
4 from strands_executive_msgs.msg import *
5 from random import random
6 from dateutil.tz import *
7 from datetime import *
8 
9 def pretty(task):
10  if len(task.action) > 0:
11  if len(task.start_node_id) > 0:
12  return '%s @ %s (task %s)' % (task.action, task.start_node_id, task.task_id)
13  else:
14  return '%s (task %s)' % (task.action, task.task_id)
15  else:
16  return 'just navigation to %s (task %s)' % (task.start_node_id, task.task_id)
17 
18 def start_time(task):
19  return datetime.fromtimestamp(task.execution_time.secs)
20 
21 def callback(data):
22  rospy.loginfo("\n\n\n\n\n\n");
23 
24  if data.currently_executing:
25  rospy.loginfo("Currently executing %s", pretty(data.execution_queue[0]))
26  rospy.loginfo("Task started at %s", start_time(data.execution_queue[0]))
27  elif len(data.execution_queue) > 0:
28  rospy.loginfo("Waiting to execute %s", pretty(data.execution_queue[0]))
29  rospy.loginfo("Execution to start at %s", start_time(data.execution_queue[0]))
30 
31  if len(data.execution_queue) > 0:
32  rospy.loginfo("A further %s tasks queued for execution", len(data.execution_queue) - 1)
33 
34 
35 if __name__ == '__main__':
36  rospy.init_node('schedule_status_printer')
37  rospy.Subscriber('/current_schedule', ExecutionStatus, callback)
38 
39  # spin() simply keeps python from exiting until this node is stopped
40  rospy.spin()
def start_time(task)
def callback(data)
def pretty(task)


task_executor
Author(s): Nick Hawes
autogenerated on Tue Mar 17 2015 20:08:13