Skip to content
Open
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
11 changes: 9 additions & 2 deletions launch/launch/launch_service.py
Original file line number Diff line number Diff line change
Expand Up @@ -94,7 +94,7 @@ def __init__(
# it being set to None by run() as it exits.
self.__loop_from_run_thread_lock = threading.RLock()
self.__loop_from_run_thread = None
self.__this_task: Optional[asyncio.Future[None]] = None
self.__this_task: Optional[asyncio.Task[None]] = None

# Used to indicate when shutdown() has been called.
self.__shutting_down = False
Expand Down Expand Up @@ -156,7 +156,14 @@ def _prune_and_count_context_completion_futures(self) -> int:
def _is_idle(self) -> bool:
number_of_entity_future_pairs = self._prune_and_count_entity_future_pairs()
number_of_entity_future_pairs += self._prune_and_count_context_completion_futures()
return number_of_entity_future_pairs == 0 and self.__context._event_queue.empty()
if self.event_loop is not None and self.__this_task is not None:
tasks = asyncio.all_tasks(self.event_loop)
tasks.remove(self.__this_task)
else:
tasks = set()
return (number_of_entity_future_pairs == 0 and
self.__context._event_queue.empty() and
len(tasks) == 0)

@contextlib.contextmanager
def _prepare_run_loop(
Expand Down
45 changes: 45 additions & 0 deletions launch/test/launch/test_execute_local.py
Original file line number Diff line number Diff line change
Expand Up @@ -178,3 +178,48 @@ def test_execute_process_with_output_dictionary():
ls = LaunchService()
ls.include_launch_description(ld)
assert 0 == ls.run()


def test_execute_process_with_shutdown_on_error():
"""Test proper shutdown of children after exception during launch."""
exited_processes = 0

def on_exit(event, context):
nonlocal exited_processes
print(event, context)
exited_processes += 1

executable_1 = ExecuteLocal(
process_description=Executable(
cmd=[sys.executable, '-c', 'while True: pass']
),
output={'stdout': 'screen', 'stderr': 'screen'},
on_exit=on_exit,
)
executable_2 = ExecuteLocal(
process_description=Executable(
cmd=[sys.executable, '-c', 'while True: pass']
),
output={'stdout': 'screen', 'stderr': 'screen'},
on_exit=on_exit,
)

# It's slightly tricky to coerce the standard implementation to fail in
# this way. However, launch_ros's Node class can fail similar to this and
# this case therefore needs to be handled correctly.
class ExecutableThatFails(ExecuteLocal):

def execute(self, context):
raise Exception('Execute Local failed')

executable_invalid = ExecutableThatFails(
process_description=Executable(
cmd=['fake_process_that_doesnt_exists']
),
output={'stdout': 'screen', 'stderr': 'screen'},
)
ld = LaunchDescription([executable_1, executable_2, executable_invalid])
ls = LaunchService()
ls.include_launch_description(ld)
assert ls.run() == 1
assert exited_processes == 2