Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Filtering out unexecutable tasks from the routine. #193

Merged
merged 3 commits into from
Apr 27, 2015
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 5 additions & 0 deletions task_executor/scripts/schedule_status.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,12 +18,17 @@ def pretty(task):
def start_time(task):
return datetime.fromtimestamp(task.execution_time.secs)

def end_time(task):
return datetime.fromtimestamp((task.execution_time + task.max_duration).secs)


def callback(data):
rospy.loginfo("\n\n\n\n\n\n");

if data.currently_executing:
rospy.loginfo("Currently executing %s", pretty(data.execution_queue[0]))
rospy.loginfo("Task started at %s", start_time(data.execution_queue[0]))
rospy.loginfo(" finish by %s", end_time(data.execution_queue[0]))
elif len(data.execution_queue) > 0:
rospy.loginfo("Waiting to execute %s", pretty(data.execution_queue[0]))
rospy.loginfo("Execution to start at %s", start_time(data.execution_queue[0]))
Expand Down
14 changes: 9 additions & 5 deletions task_executor/src/task_executor/sm_base_executor.py
Original file line number Diff line number Diff line change
Expand Up @@ -244,9 +244,11 @@ def execute_task(self, task):

# create a concurrence which monitors execution time
nav_concurrence = smach.Concurrence(outcomes=['succeeded', 'preempted', 'aborted'],
default_outcome='aborted',
default_outcome='preempted',
outcome_cb=self.outcome_cb,
child_termination_cb=concurrence_child_term_cb)
child_termination_cb=concurrence_child_term_cb,
# give states 30 seconds to service a request to shut down
termination_timeout = 30)
# register callback for logging
nav_concurrence.register_start_cb(self.nav_start_cb)
nav_concurrence.register_termination_cb(self.nav_termination_cb)
Expand Down Expand Up @@ -296,9 +298,11 @@ def execute_task(self, task):

# create a concurrence which monitors execution time along with doing the execution
action_concurrence = smach.Concurrence(outcomes=['succeeded', 'preempted', 'aborted'],
default_outcome='aborted',
default_outcome='preempted',
outcome_cb=self.outcome_cb,
child_termination_cb=concurrence_child_term_cb)
child_termination_cb=concurrence_child_term_cb,
# give states 30 seconds to service a request to shut down
termination_timeout = 30)

# register callback for logging
action_concurrence.register_start_cb(self.action_start_cb)
Expand Down Expand Up @@ -350,7 +354,7 @@ def join_smach_thread(self, timeout):
return successfully_joined

def cancel_active_task(self):
preempt_timeout_secs = 30
preempt_timeout_secs = 60
if self.task_sm is not None:
rospy.loginfo('Requesting preempt on state machine in state %s' % self.task_sm.get_active_states())
self.task_sm.request_preempt()
Expand Down
19 changes: 8 additions & 11 deletions task_executor/src/task_executor/task_routine.py
Original file line number Diff line number Diff line change
Expand Up @@ -342,7 +342,6 @@ def add_tasks(self, routines):

for task_tuple in routines:


daily_start = task_tuple[1][0]
daily_duration = task_tuple[1][1]

Expand All @@ -356,7 +355,7 @@ def add_tasks(self, routines):
# see if we can still schedule any of these today
todays_tasks = self._instantiate_tasks_for_today(new_routine)
# the false means an exception is not thrown for any out of window tasks
self._create_routine(todays_tasks, False)
self._create_routine(todays_tasks)


def _new_day(self):
Expand All @@ -371,6 +370,7 @@ def _new_day(self):

# filter the extra tasks just to make sure they're sane
now = rospy.get_rostime()

for task in extra_daily_tasks:
# check we're not too late
if now + task.max_duration < task.end_before:
Expand All @@ -384,17 +384,17 @@ def _instantiate_tasks_for_today(self, routine_tasks):
todays_tasks = [self._instantiate_for_day(self.current_routine_start, *task_tuple) for task_tuple in routine_tasks]
return todays_tasks

def _create_routine(self, tasks, throw=True):
def _create_routine(self, tasks):

schedule_now, schedule_later = self._queue_for_scheduling(tasks, throw)
schedule_now, schedule_later = self._queue_for_scheduling(tasks)

rospy.loginfo('Scheduling %s tasks now and %s later' % (len(schedule_now), len(schedule_later)))

self._delay_tasks(schedule_later)
self._schedule_tasks(schedule_now)


def _queue_for_scheduling(self, tasks, throw=True):
def _queue_for_scheduling(self, tasks):
now = rospy.get_rostime()

schedule_now = []
Expand All @@ -408,14 +408,11 @@ def _queue_for_scheduling(self, tasks, throw=True):
# print (now).secs
# print (now + task.max_duration).secs

start_time = now if now > task.start_after else task.start_after

# check we're not too late
if now + task.max_duration > task.end_before:
#
if throw:
raise RoutineException('%s is too late to schedule task %s' % (now.secs, task))
else:
rospy.logdebug('Ignoring task for today')
if start_time + task.max_duration > task.end_before:
rospy.logwarn('At %s it is not possible to schedule task %s. Ignoring task for today' % (datetime.fromtimestamp(now.secs), task))
else:
# if we're in the the window when this should be scheduled
if now > (task.start_after - self.pre_schedule_delay):
Expand Down