Skip to content

Commit

Permalink
convert ActionError
Browse files Browse the repository at this point in the history
  • Loading branch information
fred-labs committed Aug 27, 2024
1 parent 450410c commit ea3143d
Show file tree
Hide file tree
Showing 25 changed files with 81 additions and 76 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
from enum import Enum

import py_trees
from scenario_execution.actions.base_action import BaseAction
from scenario_execution.actions.base_action import BaseAction, ActionError

import docker
import tempfile
Expand Down Expand Up @@ -46,20 +46,20 @@ def setup(self, **kwargs):
# self.output_dir = tempfile.mkdtemp() # for testing: does not remove directory afterwards

if "input_dir" not in kwargs:
raise ValueError("input_dir not defined.")
raise ActionError("input_dir not defined.", action=self)
input_dir = kwargs["input_dir"]
# check docker image
self.client = docker.from_env()
image_name = 'floorplan:latest'
filterred_images = self.client.images.list(filters={'reference': image_name})
if len(filterred_images) == 0:
raise ValueError(f"Required docker image '{image_name}' does not exist.")
raise ActionError(f"Required docker image '{image_name}' does not exist.", action=self)

# check files
if not os.path.isabs(self.file_path):
self.file_path = os.path.join(input_dir, self.file_path)
if not os.path.isfile(self.file_path):
raise ValueError(f"Floorplan file {self.file_path} not found.")
raise ActionError(f"Floorplan file {self.file_path} not found.", action=self)
self.floorplan_name = os.path.splitext(os.path.basename(self.file_path))[0]

def update(self) -> py_trees.common.Status:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
import os
import py_trees
from scenario_execution_gazebo.actions.utils import SpawnUtils
from scenario_execution.actions.base_action import BaseAction
from scenario_execution.actions.base_action import BaseAction, ActionError
from shutil import which
import tempfile

Expand All @@ -31,15 +31,15 @@ def __init__(self, associated_actor, sdf_template: str, arguments: list):

def setup(self, **kwargs):
if which("xacro") is None:
raise ValueError("'xacro' not found.")
raise ActionError("'xacro' not found.", action=self)
if "input_dir" not in kwargs:
raise ValueError("input_dir not defined.")
raise ActionError("input_dir not defined.", action=self)
input_dir = kwargs["input_dir"]

if not os.path.isabs(self.sdf_template):
self.sdf_template = os.path.join(input_dir, self.sdf_template)
if not os.path.isfile(self.sdf_template):
raise ValueError(f"SDF Template {self.sdf_template} not found.")
raise ActionError(f"SDF Template {self.sdf_template} not found.", action=self)
self.tmp_file = tempfile.NamedTemporaryFile(suffix=".sdf") # for testing, do not delete temp file: delete=False

def execute(self, associated_actor, sdf_template: str, arguments: list):
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
from tf2_ros.transform_listener import TransformListener
from tf2_geometry_msgs import PoseStamped
from .gazebo_spawn_actor import GazeboSpawnActor
from scenario_execution.actions.base_action import ActionError


class GazeboRelativeSpawnActor(GazeboSpawnActor):
Expand Down Expand Up @@ -97,4 +98,4 @@ def calculate_new_pose(self):
f' w: {new_pose.pose.orientation.w} x: {new_pose.pose.orientation.x} y: {new_pose.pose.orientation.y} z: {new_pose.pose.orientation.z}' \
' } }'
except TransformException as e:
raise ValueError(f"No transform available ({self.parent_frame_id}->{self.frame_id})") from e
raise ActionError(f"No transform available ({self.parent_frame_id}->{self.frame_id})", action=self) from e
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
from rclpy.qos import QoSProfile, QoSDurabilityPolicy, QoSHistoryPolicy, QoSReliabilityPolicy
from rclpy.node import Node
import py_trees
from scenario_execution.actions.base_action import ActionError
from scenario_execution.actions.run_process import RunProcess
from .utils import SpawnUtils

Expand Down Expand Up @@ -68,7 +69,7 @@ def setup(self, **kwargs):
except KeyError as e:
error_message = "didn't find 'node' in setup's kwargs [{}][{}]".format(
self.name, self.__class__.__name__)
raise KeyError(error_message) from e
raise ActionError(error_message, action=self) from e

self.utils = SpawnUtils(logger=self.logger)

Expand All @@ -88,12 +89,12 @@ def setup(self, **kwargs):
self.entity_model, self.entity_name, self.xacro_arguments)

if not self.sdf:
raise ValueError(f'Invalid model specified ({self.entity_model})')
raise ActionError(f'Invalid model specified ({self.entity_model})', action=self)
self.current_state = SpawnActionState.MODEL_AVAILABLE

def execute(self, associated_actor, spawn_pose: list, world_name: str, xacro_arguments: list, model: str): # pylint: disable=arguments-differ
if self.entity_model != model or set(self.xacro_arguments) != set(xacro_arguments):
raise ValueError("Runtime change of model not supported.")
raise ActionError("Runtime change of model not supported.", action=self)
self.spawn_pose = spawn_pose
self.world_name = world_name

Expand Down Expand Up @@ -175,7 +176,7 @@ def get_spawn_pose(self):
f' w: {quaternion[0]} x: {quaternion[1]} y: {quaternion[2]} z: {quaternion[3]}' \
' } }'
except KeyError as e:
raise ValueError("Could not get values") from e
raise ActionError("Could not get values", action=self) from e
return pose

def set_command(self, command):
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@

from .nav2_common import NamespaceAwareBasicNavigator
from scenario_execution_ros.actions.common import get_pose_stamped, NamespacedTransformListener
from scenario_execution.actions.base_action import BaseAction
from scenario_execution.actions.base_action import BaseAction, ActionError


class InitNav2State(Enum):
Expand Down Expand Up @@ -91,7 +91,7 @@ def setup(self, **kwargs):
except KeyError as e:
error_message = "didn't find 'node' in setup's kwargs [{}][{}]".format(
self.name, self.__class__.__name__)
raise KeyError(error_message) from e
raise ActionError(error_message, action=self) from e

self.tf_buffer = Buffer()
self.tf_listener = NamespacedTransformListener(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
# SPDX-License-Identifier: Apache-2.0

import py_trees
from scenario_execution.actions.base_action import BaseAction
from scenario_execution.actions.base_action import BaseAction, ActionError
import pybullet as p
import math

Expand All @@ -30,10 +30,10 @@ def setup(self, **kwargs):
try:
tick_period: float = kwargs['tick_period']
except KeyError as e:
raise KeyError("didn't find 'tick_period' in setup's kwargs") from e
raise ActionError("didn't find 'tick_period' in setup's kwargs", action=self) from e
if not math.isclose(240 % tick_period, 0., abs_tol=1e-4):
raise ValueError(
f"Scenario Execution Tick Period of {tick_period} is not compatible with PyBullet stepping. Please set step-duration to be a multiple of 1/240s")
raise ActionError(
f"Scenario Execution Tick Period of {tick_period} is not compatible with PyBullet stepping. Please set step-duration to be a multiple of 1/240s", action=self)
self.sim_steps_per_tick = round(240 * tick_period)
self.logger.info(f"Forward simulation by {self.sim_steps_per_tick} step per scenario tick.")

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
from enum import Enum
import py_trees
import os
from scenario_execution.actions.base_action import ActionError
from scenario_execution.actions.run_process import RunProcess


Expand All @@ -36,12 +37,12 @@ def __init__(self, output_filename: str, frame_rate: float):

def setup(self, **kwargs):
if "DISPLAY" not in os.environ:
raise ValueError("capture_screen() requires environment variable 'DISPLAY' to be set.")
raise ActionError("capture_screen() requires environment variable 'DISPLAY' to be set.", action=self)

if kwargs['output_dir']:
if not os.path.exists(kwargs['output_dir']):
raise ValueError(
f"Specified destination dir '{kwargs['output_dir']}' does not exist")
raise ActionError(
f"Specified destination dir '{kwargs['output_dir']}' does not exist", action=self)
self.output_dir = kwargs['output_dir']

def execute(self, output_filename: str, frame_rate: float): # pylint: disable=arguments-differ
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,7 @@ def get_blackboard_namespace(node: ParameterDeclaration):

def register_access_to_associated_actor_variable(self, variable_name):
if not self._model.actor:
raise ValueError("Model does not have 'actor'.")
raise ActionError("Model does not have 'actor'.", action=self)
blackboard = self.get_blackboard_client()
model_blackboard_name = self._model.actor.get_fully_qualified_var_name(include_scenario=False)
model_blackboard_name += "/" + variable_name
Expand Down
4 changes: 2 additions & 2 deletions scenario_execution/scenario_execution/actions/log.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@

import py_trees
from py_trees.common import Status
from scenario_execution.actions.base_action import BaseAction
from scenario_execution.actions.base_action import BaseAction, ActionError


class Log(BaseAction):
Expand All @@ -38,7 +38,7 @@ def update(self) -> py_trees.common.Status:
if not self.published:
self.published = True
if not self.msg:
raise ValueError("log(): Empty message.")
raise ActionError("log(): Empty message.", action=self)
self.logger.info(f"{self.msg}")

return Status.SUCCESS
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
from lifecycle_msgs.srv import GetState
from lifecycle_msgs.msg import TransitionEvent
from scenario_execution_ros.actions.conversions import get_qos_preset_profile
from scenario_execution.actions.base_action import BaseAction
from scenario_execution.actions.base_action import BaseAction, ActionError
from enum import Enum
from queue import Queue
from collections import deque
Expand Down Expand Up @@ -56,7 +56,7 @@ def setup(self, **kwargs):
except KeyError as e:
error_message = "didn't find 'node' in setup's kwargs [{}][{}]".format(
self.name, self.__class__.__name__)
raise KeyError(error_message) from e
raise ActionError(error_message, action=self) from e

topic_transition_event_name = "/" + self.node_name + "/transition_event"
self.subscription = self.node.create_subscription(
Expand All @@ -67,15 +67,15 @@ def setup(self, **kwargs):

def execute(self, node_name: str, state_sequence: list, allow_initial_skip: bool, fail_on_unexpected: bool, keep_running: bool):
if self.node_name != node_name or self.state_sequence != state_sequence:
raise ValueError("Runtime change of arguments 'name', 'state_sequence not supported.")
raise ActionError("Runtime change of arguments 'name', 'state_sequence not supported.", action=self)

if all(isinstance(state, tuple) and len(state) == 2 for state in self.state_sequence):
self.state_sequence = [state[0] for state in self.state_sequence]
else:
allowed_states = ['unconfigured', 'inactive', 'active', 'finalized']
for value in self.state_sequence:
if value not in allowed_states:
raise ValueError("The specified state_sequence is not valid")
raise ActionError("The specified state_sequence is not valid", action=self)
self.state_sequence = deque(self.state_sequence)
self.allow_initial_skip = allow_initial_skip
self.fail_on_unexpected = fail_on_unexpected
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
import time
import tf2_ros
from .common import NamespacedTransformListener
from scenario_execution.actions.base_action import BaseAction
from scenario_execution.actions.base_action import BaseAction, ActionError
from tf2_ros import TransformException # pylint: disable= no-name-in-module
import math

Expand Down Expand Up @@ -51,7 +51,7 @@ def setup(self, **kwargs):
except KeyError as e:
error_message = "didn't find 'node' in setup's kwargs [{}][{}]".format(
self.name, self.__class__.__name__)
raise KeyError(error_message) from e
raise ActionError(error_message, action=self) from e

self.feedback_message = f"Waiting for transform {self.parent_frame_id} --> {self.frame_id}" # pylint: disable= attribute-defined-outside-init
self.tf_buffer = tf2_ros.Buffer()
Expand All @@ -67,7 +67,7 @@ def setup(self, **kwargs):

def execute(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):
if self.tf_topic_namespace != tf_topic_namespace:
raise ValueError("Runtime change of argument 'tf_topic_namespace' not supported.")
raise ActionError("Runtime change of argument 'tf_topic_namespace' not supported.", action=self)
self.frame_id = frame_id
self.parent_frame_id = parent_frame_id
self.timeout = timeout
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@
import importlib
import time
from scenario_execution_ros.actions.conversions import get_comparison_operator, get_qos_preset_profile
from scenario_execution.actions.base_action import BaseAction
from scenario_execution.actions.base_action import BaseAction, ActionError


class AssertTopicLatency(BaseAction):
Expand Down Expand Up @@ -51,17 +51,17 @@ def setup(self, **kwargs):
except KeyError as e:
error_message = "didn't find 'node' in setup's kwargs [{}][{}]".format(
self.name, self.__class__.__name__)
raise KeyError(error_message) from e
raise ActionError(error_message, action=self) from e

success = self.check_topic()
if not success and self.wait_for_first_message:
raise ValueError("Invalid topic or type specified.")
raise ActionError("Invalid topic or type specified.", action=self)
elif not success and not self.wait_for_first_message:
raise ValueError("Topic type must be specified. Please provide a valid topic type.")
raise ActionError("Topic type must be specified. Please provide a valid topic type.", action=self)

def execute(self, topic_name: str, topic_type: str, latency: float, comparison_operator: bool, rolling_average_count: int, wait_for_first_message: bool):
if self.timer != 0:
raise ValueError("Action does not yet support to get retriggered")
raise ActionError("Action does not yet support to get retriggered", action=self)
self.timer = time.time()

def update(self) -> py_trees.common.Status:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
from nav_msgs.msg import Odometry
from py_trees.common import Status
import py_trees
from scenario_execution.actions.base_action import BaseAction
from scenario_execution.actions.base_action import BaseAction, ActionError


class OdometryDistanceTraveled(BaseAction):
Expand Down Expand Up @@ -49,7 +49,7 @@ def setup(self, **kwargs):
except KeyError as e:
error_message = "didn't find 'node' in setup's kwargs [{}][{}]".format(
self.name, self.__class__.__name__)
raise KeyError(error_message) from e
raise ActionError(error_message, action=self) from e
self.callback_group = rclpy.callback_groups.MutuallyExclusiveCallbackGroup()
namespace = self.namespace
if self.namespace_override:
Expand All @@ -59,7 +59,7 @@ def setup(self, **kwargs):

def execute(self, associated_actor, distance: float, namespace_override: str):
if self.namespace != associated_actor["namespace"] or self.namespace_override != namespace_override:
raise ValueError("Runtime change of namespace not supported.")
raise ActionError("Runtime change of namespace not supported.", action=self)
self.distance_expected = distance
self.distance_traveled = 0.0
self.previous_x = 0
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
from rosidl_runtime_py.set_message import set_message_fields
import py_trees # pylint: disable=import-error
from action_msgs.msg import GoalStatus
from scenario_execution.actions.base_action import BaseAction
from scenario_execution.actions.base_action import BaseAction, ActionError


class ActionCallActionState(Enum):
Expand Down Expand Up @@ -69,15 +69,15 @@ def setup(self, **kwargs):
except KeyError as e:
error_message = "didn't find 'node' in setup's kwargs [{}][{}]".format(
self.name, self.__class__.__name__)
raise KeyError(error_message) from e
raise ActionError(error_message, action=self) from e

datatype_in_list = self.action_type_string.split(".")
try:
self.action_type = getattr(
importlib.import_module(".".join(datatype_in_list[0:-1])),
datatype_in_list[-1])
except ValueError as e:
raise ValueError(f"Invalid action_type '{self.action_type}':") from e
raise ActionError(f"Invalid action_type '{self.action_type}': {e}", action=self) from e

client_kwargs = {
"callback_group": self.cb_group,
Expand All @@ -92,7 +92,7 @@ def setup(self, **kwargs):

def execute(self, action_name: str, action_type: str, data: str, transient_local: bool = False):
if self.action_name != action_name or self.action_type_string != action_type or self.transient_local != transient_local:
raise ValueError(f"Updating action_name or action_type_string not supported.")
raise ActionError(f"Updating action_name or action_type_string not supported.", action=self)

self.parse_data(data)
self.current_state = ActionCallActionState.IDLE
Expand All @@ -103,7 +103,7 @@ def parse_data(self, data):
trimmed_data = data.encode('utf-8').decode('unicode_escape')
self.data = literal_eval(trimmed_data)
except Exception as e: # pylint: disable=broad-except
raise ValueError(f"Error while parsing sevice call data:") from e
raise ActionError(f"Error while parsing sevice call data:", action=self) from e

def update(self) -> py_trees.common.Status:
"""
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
from enum import Enum

import py_trees
from scenario_execution.actions.base_action import ActionError
from scenario_execution.actions.run_process import RunProcess
import shutil
import signal
Expand Down Expand Up @@ -50,12 +51,11 @@ def setup(self, **kwargs):
set up
"""
if "output_dir" not in kwargs:
raise ValueError("output_dir not defined.")
raise ActionError("output_dir not defined.", action=self)

if kwargs['output_dir']:
if not os.path.exists(kwargs['output_dir']):
raise ValueError(
f"Specified destination dir '{kwargs['output_dir']}' does not exist")
raise ActionError(f"Specified destination dir '{kwargs['output_dir']}' does not exist", action=self)
self.output_dir = kwargs['output_dir']

def execute(self, topics: list, timestamp_suffix: bool, hidden_topics: bool, storage: str, use_sim_time: bool): # pylint: disable=arguments-differ
Expand Down
Loading

0 comments on commit ea3143d

Please sign in to comment.