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

add additional modifiers #143

Merged
merged 3 commits into from
Aug 1, 2024
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
1 change: 1 addition & 0 deletions .github/workflows/Dockerfile
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@ RUN --mount=type=bind,source=.,target=/scenario_execution \
tk \
libgl1 && \
xargs -a /scenario_execution/deb_requirements.txt apt-get install -y --no-install-recommends && \
xargs -a /scenario_execution/libs/scenario_execution_kubernetes/deb_requirements.txt apt-get install -y --no-install-recommends && \
rosdep update --rosdistro=${ROS_DISTRO} && \
rosdep install --rosdistro=${ROS_DISTRO} --from-paths /scenario_execution/ --ignore-src -r -y && \
rm -rf /var/lib/apt/lists/*
Expand Down
42 changes: 32 additions & 10 deletions docs/libraries.rst
Original file line number Diff line number Diff line change
Expand Up @@ -310,6 +310,36 @@ Modifier to set a timeout for a sub-tree.
-
- Maximum number of permitted failures

``failure_is_running()``
""""""""""""""""""""""""

Don't stop running.

``failure_is_success()``
""""""""""""""""""""""""

Be positive, always succeed.

``running_is_failure()``
""""""""""""""""""""""""

Got to be snappy! We want results...yesterday.

``running_is_success()``
""""""""""""""""""""""""

Don't hang around...

``success_is_failure()``
""""""""""""""""""""""""

Be depressed, always fail.

``success_is_running()``
""""""""""""""""""""""""

The tickling never ends...


Kubernetes
----------
Expand Down Expand Up @@ -712,7 +742,7 @@ Checks for the state of a `lifecycle-managed <https://design.ros2.org/articles/n
``assert_tf_moving()``
""""""""""""""""""""""

Checks that a tf ``frame_id`` keeps moving in respect to a ``parent_frame_id``. If there is no movement within ``timeout`` the action ends, depending on ``fail_on_finish``, either with success or failure. Speeds below ``threshold_translation`` and ``threshold_rotation`` are discarded. By default the action waits for the first transform to get available before starting the timeout timer. This can be changed by setting ``wait_for_first_transform`` to ``false``. If the tf topics are not available on ``/tf`` and ``/tf_static`` you can specify a namespace by setting ``tf_topic_namespace``.
Checks that a tf ``frame_id`` keeps moving in respect to a ``parent_frame_id``. If there is no movement within ``timeout`` the action with failure. Speeds below ``threshold_translation`` and ``threshold_rotation`` are discarded. By default the action waits for the first transform to get available before starting the timeout timer. This can be changed by setting ``wait_for_first_transform`` to ``false``. If the tf topics are not available on ``/tf`` and ``/tf_static`` you can specify a namespace by setting ``tf_topic_namespace``.

.. list-table::
:widths: 15 15 5 65
Expand Down Expand Up @@ -743,10 +773,6 @@ Checks that a tf ``frame_id`` keeps moving in respect to a ``parent_frame_id``.
- ``angular_rate``
- ``0.01radps``
- Rotational speed below this threshold is skipped.
* - ``fail_on_finish``
- ``bool``
- ``true``
- If true and there is no movement, the action fails. Otherwise it succeeds.
* - ``wait_for_first_transform``
- ``bool``
- ``true``
Expand All @@ -763,7 +789,7 @@ Checks that a tf ``frame_id`` keeps moving in respect to a ``parent_frame_id``.
``assert_topic_latency()``
""""""""""""""""""""""""""

Check the latency of the specified topic (in system time). If the check with ``comparison_operator`` gets true, the action ends, depending on ``fail_on_finish``, either with success or failure.
Check the latency of the specified topic (in system time). If the check with ``comparison_operator`` gets true, the action ends with failure.

.. list-table::
:widths: 15 15 5 65
Expand All @@ -786,10 +812,6 @@ Check the latency of the specified topic (in system time). If the check with ``c
- ``comparison_operator``
- ``comparison_operator!le``
- operator to compare latency time.
* - ``fail_on_finish``
- ``bool``
- ``true``
- If false action success, if comparison is true.
* - ``rolling_average_count``
- ``int``
- ``1``
Expand Down
18 changes: 18 additions & 0 deletions scenario_execution/scenario_execution/lib_osc/helpers.osc
Original file line number Diff line number Diff line change
Expand Up @@ -44,3 +44,21 @@ modifier retry:
modifier timeout:
# modifier to set a timeout for a subtree
duration: time # time to wait

modifier failure_is_running
# don't stop running

modifier failure_is_success
# be positive, always succeed

modifier running_is_failure
# got to be snappy! We want results...yesterday

modifier running_is_success
# don't hang around...

modifier success_is_failure
# be depressed, always fail

modifier success_is_running
# the tickling never ends...
23 changes: 18 additions & 5 deletions scenario_execution/scenario_execution/model/model_to_py_tree.py
Original file line number Diff line number Diff line change
Expand Up @@ -204,21 +204,34 @@ def compare_method_arguments(self, method, expected_args, behavior_name, node):
return method_args, error_string

def create_decorator(self, node: ModifierDeclaration, resolved_values):
available_modifiers = ["repeat", "inverter", "timeout", "retry"]
available_modifiers = ["repeat", "inverter", "timeout", "retry", "failure_is_running", "failure_is_success",
"running_is_failure", "running_is_success", "success_is_failure", "success_is_running"]
if node.name not in available_modifiers:
raise OSC2ParsingError(
msg=f'Unknown modifier "{node.name}". Available modifiers {available_modifiers}.', context=node.get_ctx())
parent = self.__cur_behavior.parent
if parent:
parent.children.remove(self.__cur_behavior)
if node.name == "repeat":
instance = py_trees.decorators.Repeat(name="Repeat", child=self.__cur_behavior, num_success=resolved_values["count"])
instance = py_trees.decorators.Repeat(name="repeat", child=self.__cur_behavior, num_success=resolved_values["count"])
elif node.name == "inverter":
instance = py_trees.decorators.Inverter(name="Inverter", child=self.__cur_behavior)
instance = py_trees.decorators.Inverter(name="inverter", child=self.__cur_behavior)
elif node.name == "timeout":
instance = py_trees.decorators.Timeout(name="Timeout", child=self.__cur_behavior, duration=resolved_values["duration"])
instance = py_trees.decorators.Timeout(name="timeout", child=self.__cur_behavior, duration=resolved_values["duration"])
elif node.name == "retry":
instance = py_trees.decorators.Retry(name="Retry", child=self.__cur_behavior, num_failures=resolved_values["count"])
instance = py_trees.decorators.Retry(name="retry", child=self.__cur_behavior, num_failures=resolved_values["count"])
elif node.name == "failure_is_running":
instance = py_trees.decorators.FailureIsRunning(name="failure_is_running", child=self.__cur_behavior)
elif node.name == "failure_is_success":
instance = py_trees.decorators.FailureIsSuccess(name="failure_is_success", child=self.__cur_behavior)
elif node.name == "running_is_failure":
instance = py_trees.decorators.RunningIsFailure(name="running_is_failure", child=self.__cur_behavior)
elif node.name == "running_is_success":
instance = py_trees.decorators.RunningIsSuccess(name="running_is_success", child=self.__cur_behavior)
elif node.name == "success_is_failure":
instance = py_trees.decorators.SuccessIsFailure(name="success_is_failure", child=self.__cur_behavior)
elif node.name == "success_is_running":
instance = py_trees.decorators.SuccessIsRunning(name="success_is_running", child=self.__cur_behavior)
else:
raise ValueError('unknown.')

Expand Down
100 changes: 100 additions & 0 deletions scenario_execution/test/test_scenario_modifier.py
Original file line number Diff line number Diff line change
Expand Up @@ -376,3 +376,103 @@ def test_modifier_in_scenario_last_fails(self):
"""
self.execute(scenario_content)
self.assertFalse(self.scenario_execution.process_results())

def test_modifier_failure_is_running(self):
scenario_content = """
import osc.helpers

scenario test:
do parallel:
serial:
run_process("false") with:
failure_is_running()
emit fail
serial:
wait elapsed(2s)
emit end
"""
self.execute(scenario_content)
self.assertTrue(self.scenario_execution.process_results())

def test_modifier_failure_is_success(self):
scenario_content = """
import osc.helpers

scenario test:
do parallel:
serial:
run_process("false") with:
failure_is_success()
emit end
serial:
wait elapsed(2s)
emit fail
"""
self.execute(scenario_content)
self.assertTrue(self.scenario_execution.process_results())

def test_modifier_running_is_failure(self):
scenario_content = """
import osc.helpers

scenario test:
do parallel:
serial:
run_process("sleep 10") with:
running_is_failure()
serial:
wait elapsed(5s)
emit end
"""
self.execute(scenario_content)
self.assertFalse(self.scenario_execution.process_results())

def test_modifier_running_is_success(self):
scenario_content = """
import osc.helpers

scenario test:
do parallel:
serial:
run_process("sleep 10") with:
running_is_success()
emit end
serial:
wait elapsed(5s)
emit fail
"""
self.execute(scenario_content)
self.assertTrue(self.scenario_execution.process_results())

def test_modifier_success_is_failure(self):
scenario_content = """
import osc.helpers

scenario test:
do parallel:
serial:
run_process("true") with:
success_is_failure()
serial:
wait elapsed(5s)
emit end
"""
self.execute(scenario_content)
self.assertFalse(self.scenario_execution.process_results())

def test_modifier_success_is_running(self):
scenario_content = """
import osc.helpers

scenario test:
do parallel:
serial:
run_process("true") with:
success_is_running()
emit fail
serial:
wait elapsed(5s)
emit end
"""
self.execute(scenario_content)
self.assertTrue(self.scenario_execution.process_results())
Original file line number Diff line number Diff line change
Expand Up @@ -27,12 +27,11 @@

class AssertTfMoving(BaseAction):

def __init__(self, frame_id: str, parent_frame_id: str, timeout: int, threshold_translation: float, threshold_rotation: float, fail_on_finish: bool, wait_for_first_transform: bool, tf_topic_namespace: str, use_sim_time: bool):
def __init__(self, frame_id: str, parent_frame_id: str, timeout: int, threshold_translation: float, threshold_rotation: float, wait_for_first_transform: bool, tf_topic_namespace: str, use_sim_time: bool):
super().__init__()
self.frame_id = frame_id
self.parent_frame_id = parent_frame_id
self.timeout = timeout
self.fail_on_finish = fail_on_finish
self.threshold_translation = threshold_translation
self.threshold_rotation = threshold_rotation
self.wait_for_first_transform = wait_for_first_transform
Expand Down Expand Up @@ -93,13 +92,9 @@ def update(self) -> py_trees.common.Status:
if not self.start_timeout:
self.timer = time.time()
self.start_timeout = True
elif now - self.timer > self.timeout and self.fail_on_finish:
elif now - self.timer > self.timeout:
self.feedback_message = f"Timeout: No movement detected for {self.timeout} seconds." # pylint: disable= attribute-defined-outside-init
result = py_trees.common.Status.FAILURE
elif now - self.timer > self.timeout and not self.fail_on_finish:
self.logger.error("Timeout: No movement detected for {} seconds.".format(self.timeout))
self.feedback_message = f"Timeout: No movement detected for {self.timeout} seconds." # pylint: disable= attribute-defined-outside-init
result = py_trees.common.Status.SUCCESS
else:
self.feedback_message = "Frame is not moving." # pylint: disable= attribute-defined-outside-init
result = py_trees.common.Status.RUNNING
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,14 +26,13 @@

class AssertTopicLatency(BaseAction):

def __init__(self, topic_name: str, topic_type: str, latency: float, comparison_operator: bool, fail_on_finish: bool, rolling_average_count: int, wait_for_first_message: bool):
def __init__(self, topic_name: str, topic_type: str, latency: float, comparison_operator: bool, rolling_average_count: int, wait_for_first_message: bool):
super().__init__()
self.topic_name = topic_name
self.topic_type = topic_type
self.latency = latency
self.comparison_operator_feedback = comparison_operator[0]
self.comparison_operator = get_comparison_operator(comparison_operator)
self.fail_on_finish = fail_on_finish
self.rolling_average_count = rolling_average_count
self.rolling_average_count_queue = deque(maxlen=rolling_average_count)
self.wait_for_first_message = wait_for_first_message
Expand Down Expand Up @@ -86,12 +85,9 @@ def update(self) -> py_trees.common.Status:
if self.comparison_operator(self.average_latency, self.latency):
result = py_trees.common.Status.RUNNING
self.feedback_message = f'Latency within range: expected {self.comparison_operator_feedback} {self.latency} s, actual {self.average_latency} s' # pylint: disable= attribute-defined-outside-init
if not self.comparison_operator(self.average_latency, self.latency) and self.fail_on_finish:
else:
result = py_trees.common.Status.FAILURE
self.feedback_message = f'Latency not within range: expected {self.comparison_operator_feedback} {self.latency} s, actual {self.average_latency} s' # pylint: disable= attribute-defined-outside-init
elif not self.comparison_operator(self.average_latency, self.latency):
result = py_trees.common.Status.SUCCESS
self.feedback_message = f'Latency not within range: expected {self.comparison_operator_feedback} {self.latency} s, actual {self.average_latency} s' # pylint: disable= attribute-defined-outside-init
else:
result = py_trees.common.Status.RUNNING
return result
Expand Down
13 changes: 5 additions & 8 deletions scenario_execution_ros/scenario_execution_ros/lib_osc/ros.osc
Original file line number Diff line number Diff line change
Expand Up @@ -42,27 +42,24 @@ action assert_lifecycle_state:
keep_running: bool = true # if true, the action keeps running while the last state in the state_sequence remains

action assert_tf_moving:
# Checks that a tf frame_id keeps moving in respect to a parent_frame_id. If there is no movement within timeout the action ends,
# depending on fail_on_finish, either with success or failure. Speeds below threshold_translation and threshold_rotation
# are discarded. By default the action waits for the first transform to get available before starting the timeout timer.
# This can be changed by setting wait_for_first_transform to false. If the tf topics are not available on /tf and /tf_static
# you can specify a namespace by setting tf_topic_namespace.
# Checks that a tf frame_id keeps moving in respect to a parent_frame_id. If there is no movement within timeout the action ends with failure.
# Speeds below threshold_translation and threshold_rotation are discarded. By default the action waits for the first transform to get available
# before starting the timeout timer. This can be changed by setting wait_for_first_transform to false. If the tf topics are not available
# on /tf and /tf_static you can specify a namespace by setting tf_topic_namespace.
frame_id: string # frame_id to check for movement
parent_frame_id: string = "map" # parent frame_id against which the movement is checked
timeout: time # timeout without movement
threshold_translation: speed = 0.01mps # translation speed, below this threshold is skipped
threshold_rotation: angular_rate = 0.01radps # rotational speed, below this threshold is skipped
fail_on_finish: bool = true # if false, the action should success if no movement
wait_for_first_transform: bool = true # start measuring with the first received message
tf_topic_namespace: string = '' # if set, it's used as namespace
use_sim_time: bool = false # in simulation, we need to look up the transform at a different time as the scenario execution node is not allowed to use the sim time

action assert_topic_latency:
# Check the latency of the specified topic (in system time). If the check with comparison_operator gets true, the action ends, depending on fail_on_finish, either with success or failure.
# Check the latency of the specified topic (in system time). If the check with comparison_operator gets true, the action ends with failure.
topic_name: string # topic name to wait for message
latency: time # the time to compare against
comparison_operator: comparison_operator = comparison_operator!le # the comparison is done using the python operator module
fail_on_finish: bool = true # if false, the action should succeed if comparison is true
rolling_average_count: int = 1 # the check is done aganist the rolling average over x elements
wait_for_first_message: bool = true # start measuring with the first received message
topic_type: string # class of message type, only required when wait_for_first_message is set to false (e.g. std_msgs.msg.String)
Expand Down
9 changes: 5 additions & 4 deletions scenario_execution_ros/test/test_assert_tf_moving.py
Original file line number Diff line number Diff line change
Expand Up @@ -123,7 +123,6 @@ def tearDown(self):
# DEFAULT VALUES
# threshold_translation: 0.01 mps (meters per second)
# threshold_rotation: 0.01 radps (radians per second)
# fail_on_finish: True
# wait_for_first_transform: True
# tf_topic_namespace: (optional)
# use_sim_time: (optional)
Expand All @@ -140,7 +139,7 @@ def tearDown(self):
# Case 4: Test with threshold_translation set to 1 mps. The test fails with timeout as the average threshold of the robot_moving frame is less than 1 mps (meters per second).
# Case 5: Test with threshold_rotation set to 5 radps. The test fails with timeout as the average threshold of the robot_rotating frame is less than 5 radps (radians per second).

# 3. fail_on_finish: False
# 3. failure_is_success
# Case 6: Test succeeds if no movement is observed between frames.

# 4. wait_for_first_transform: False
Expand All @@ -161,6 +160,7 @@ def test_case_1(self):
self.execute(scenario_content)
self.assertFalse(self.scenario_execution_ros.process_results())

@unittest.skip(reason="unstable on CI")
def test_case_2(self):
scenario_content = """
import osc.ros
Expand Down Expand Up @@ -222,13 +222,14 @@ def test_case_5(self):

def test_case_6(self):
scenario_content = """
import osc.helpers
import osc.ros
scenario test_assert_tf_moving:
do serial:
assert_tf_moving(
frame_id: 'robot',
timeout: 2s,
fail_on_finish: false)
timeout: 2s) with:
failure_is_success()
emit end
"""
self.execute(scenario_content)
Expand Down
Loading