Skip to content

Commit

Permalink
Merge pull request #131 from LucaKro/failure_handling
Browse files Browse the repository at this point in the history
[FailureHandling] Adjusted docstrings, and some code improvements for PR
  • Loading branch information
sunava authored Aug 21, 2024
2 parents a3df55d + 43f1843 commit 11d7ba9
Show file tree
Hide file tree
Showing 2 changed files with 48 additions and 54 deletions.
94 changes: 43 additions & 51 deletions src/pycram/failure_handling.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,8 @@
from .datastructures.enums import State
from .designator import DesignatorDescription
from .plan_failures import PlanFailure
from threading import Lock
from typing import Union
from typing_extensions import Union, Tuple, Any, List
from .language import Language, Monitor


Expand All @@ -18,7 +19,8 @@ def __init__(self, designator_description: Union[DesignatorDescription, Monitor]
"""
Initializes a new instance of the FailureHandling class.
:param designator_description: The description or context of the task or process for which the failure handling is being set up.
:param Union[DesignatorDescription, Monitor] designator_description: The description or context of the task
or process for which the failure handling is being set up.
"""
self.designator_description = designator_description

Expand All @@ -40,15 +42,10 @@ class Retry(FailureHandling):
This class represents a specific failure handling strategy where the system
attempts to retry a failed action a certain number of times before giving up.
Attributes:
max_tries (int): The maximum number of attempts to retry the action.
Inherits:
All attributes and methods from the FailureHandling class.
Overrides:
perform(): Implements the retry logic.
"""
max_tries: int
"""
The maximum number of attempts to retry the action.
"""

def __init__(self, designator_description: DesignatorDescription, max_tries: int = 3):
Expand All @@ -61,7 +58,7 @@ def __init__(self, designator_description: DesignatorDescription, max_tries: int
super().__init__(designator_description)
self.max_tries = max_tries

def perform(self):
def perform(self) -> Tuple[State, List[Any]]:
"""
Implementation of the retry mechanism.
Expand All @@ -88,27 +85,22 @@ class RetryMonitor(FailureHandling):
This class represents a specific failure handling strategy that allows us to retry a demo that is
being monitored, in case that monitoring condition is triggered.
Attributes:
max_tries (int): The maximum number of attempts to retry the action.
recovery (dict): A dictionary that maps exception types to recovery actions
Inherits:
All attributes and methods from the FailureHandling class.
Overrides:
perform(): Implements the retry logic.
"""
max_tries: int
"""
The maximum number of attempts to retry the action.
"""
recovery: dict
"""
A dictionary that maps exception types to recovery actions
"""

def __init__(self, designator_description: Monitor, max_tries: int = 3, recovery: dict = None):
"""
Initializes a new instance of the Retry class.
Args:
designator_description (DesignatorDescription): The description or context
of the task or process for which the retry mechanism is being set up.
max_tries (int, optional): The maximum number of attempts to retry. Defaults to 3.
recovery (dict, optional): A dictionary that maps exception types to recovery actions. Defaults to None.
Initializes a new instance of the RetryMonitor class.
:param Monitor designator_description: The Monitor instance to be used.
:param int max_tries: The maximum number of attempts to retry. Defaults to 3.
:param dict recovery: A dictionary that maps exception types to recovery actions. Defaults to None.
"""
super().__init__(designator_description)
self.max_tries = max_tries
Expand All @@ -126,37 +118,37 @@ def __init__(self, designator_description: Monitor, max_tries: int = 3, recovery
raise TypeError("Values in the recovery dictionary must be instances of the Language class.")
self.recovery = recovery

def perform(self):
def perform(self) -> Tuple[State, List[Any]]:
"""
Implementation of the retry mechanism.
This method attempts to perform the Monitor + plan specified in the designator_description.
If the action fails, it is retried up to max_tries times. If all attempts fail,
the last exception is raised. In every loop, we need to clear the kill_event, and set all
relevant 'interrupted' variables to False, to make sure the Monitor and plan are executed
properly again
This method attempts to perform the Monitor + plan specified in the designator_description. If the action
fails, it is retried up to max_tries times. If all attempts fail, the last exception is raised. In every
loop, we need to clear the kill_event, and set all relevant 'interrupted' variables to False, to make sure
the Monitor and plan are executed properly again.
Raises:
PlanFailure: If all retry attempts fail.
:raises PlanFailure: If all retry attempts fail.
Returns:
The state of the execution performed, as well as a flattened list of the results, in the correct order
:return: The state of the execution performed, as well as a flattened list of the
results, in the correct order
"""

def reset_interrupted(child):
if hasattr(child, "interrupted"):
child.interrupted = False
for sub_child in getattr(child, "children", []):
reset_interrupted(sub_child)
child.interrupted = False
try:
for sub_child in child.children:
reset_interrupted(sub_child)
except AttributeError:
pass

def flatten(result):
flattened_list = []
for item in result:
if isinstance(item, list):
flattened_list.extend(item)
else:
flattened_list.append(item)
return flattened_list
if result:
for item in result:
if isinstance(item, list):
flattened_list.extend(item)
else:
flattened_list.append(item)
return flattened_list
return None

status, res = None, None
with self.lock:
Expand Down
8 changes: 5 additions & 3 deletions src/pycram/language.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
# used for delayed evaluation of typing until python 3.11 becomes mainstream
from __future__ import annotations

import queue
from queue import Queue
import rospy
from typing_extensions import Iterable, Optional, Callable, Dict, Any, List, Union, Tuple
from anytree import NodeMixin, Node, PreOrderIter
Expand Down Expand Up @@ -261,7 +261,7 @@ def __init__(self, condition: Union[Callable, Fluent] = None):
"""
super().__init__(None, None)
self.kill_event = threading.Event()
self.exception_queue = queue.Queue()
self.exception_queue = Queue()
if callable(condition):
self.condition = Fluent(condition)
elif isinstance(condition, Fluent):
Expand All @@ -282,8 +282,10 @@ def check_condition():
cond = self.condition.get_value()
if cond:
for child in self.children:
if hasattr(child, 'interrupt'):
try:
child.interrupt()
except NotImplementedError:
pass
if isinstance(cond, type) and issubclass(cond, Exception):
self.exception_queue.put(cond)
else:
Expand Down

0 comments on commit 11d7ba9

Please sign in to comment.