Skip to content
This repository was archived by the owner on Jul 16, 2025. It is now read-only.

Commit 03486e6

Browse files
author
fred-labs
authored
Initialize osc args only once, either in init or execute (#167)
1 parent a426b68 commit 03486e6

File tree

43 files changed

+221
-220
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

43 files changed

+221
-220
lines changed

docs/development.rst

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -95,8 +95,9 @@ Implement an Action
9595
- Make use of ``kwargs['logger']``, available in ``setup()``
9696
- If you want to draw markers for RViz, use ``kwargs['marker_handler']``, available in ``setup()`` (with ROS backend)
9797
- Use arguments from ``__init__()`` for a longer running initialization in ``setup()`` and the arguments from ``execute()`` to set values just before executing the action.
98-
- ``__init__()`` does not need to contain all osc2-defined arguments. This can be convenient as variable argument resolving might not be available during ``__init__()``.
99-
- ``execute()`` contains all osc2-arguments.
98+
- ``__init__()`` and ``setup()`` are called once, ``execute()`` might be called multiple times.
99+
- osc2 arguments can only be consumed once, either in ``__init__()`` or ``execute()``. Exception: If an ``associated_actor`` exists, it's an argument of both methods.
100+
- Arguments that need late resolving (e.g. referring to variables or external methods) need to be consumed in ``execute()``.
100101
- ``setup()`` provides several arguments that might be useful:
101102
- ``input_dir``: Directory containing the scenario file
102103
- ``output_dir``: If given on command-line, contains the directory to save output to

docs/tutorials.rst

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -91,7 +91,7 @@ Then, we can write the implementation of action plugin in Python.
9191
9292
class CustomAction(BaseAction):
9393
94-
def __init__(self, data: str):
94+
def __init__(self):
9595
super().__init__()
9696
9797
def execute(self, data: str):
@@ -105,9 +105,9 @@ Then, we can write the implementation of action plugin in Python.
105105
In the example, we created a custom action plugin to print a message on the
106106
screen. The first step is to create an action implementation, based on the class ``BaseAction``.
107107
There are two methods that can be overloaded in order to receive the action arguments as defined in the osc file.
108-
The first is the ``__init__()`` function which gets the argument values as they get initialized during parsing the scenario file.
109-
The second is the ``execute()`` function which gets the argument values as they are currently defined at the time the action gets executed.
110-
This allows to initialize the action and then set the latest values just before the action gets triggered.
108+
109+
1. ``__init__()`` function which is called once for each action instance. It can consume any of the arguments defined within the scenario file. If there are long-running initialization tasks, it is good practice to execute those within ``setup()``, which is also only called once.
110+
2. ``execute()`` function is called when the action gets active. It receives all remaining arguments, that are not consumed within ``__init__()``. It is good practice to consume as many arguments as possible here, to allow late-resolving (e.g. receiving the latest value from variables or external methods).
111111

112112
The action plugin ``custom_action`` only defines one parameter ``data``, so the behavior only has to accept ``data`` as an
113113
argument. Then, override the ``update()`` function to define how the

examples/example_library/example_library/actions/custom_action.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@
2121

2222
class CustomAction(BaseAction):
2323

24-
def __init__(self, data: str): # get action arguments, at the time of initialization
24+
def __init__(self): # get action arguments, at the time of initialization
2525
super().__init__()
2626

2727
def execute(self, data: str): # get action arguments, at the time of execution (may got updated during scenario execution)

libs/scenario_execution_floorplan_dsl/scenario_execution_floorplan_dsl/actions/generate_gazebo_world.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,7 @@
2424

2525
class GenerateGazeboWorld(BaseAction):
2626

27-
def __init__(self, associated_actor, sdf_template: str, arguments: list):
27+
def __init__(self, associated_actor, sdf_template: str):
2828
super().__init__()
2929
self.sdf_template = sdf_template
3030
self.spawn_utils = SpawnUtils(self.logger)
@@ -42,7 +42,7 @@ def setup(self, **kwargs):
4242
raise ActionError(f"SDF Template {self.sdf_template} not found.", action=self)
4343
self.tmp_file = tempfile.NamedTemporaryFile(suffix=".sdf") # for testing, do not delete temp file: delete=False
4444

45-
def execute(self, associated_actor, sdf_template: str, arguments: list):
45+
def execute(self, associated_actor, arguments: list):
4646
self.arguments_string = ""
4747
for elem in arguments:
4848
self.arguments_string += f'{elem["key"]}:={elem["value"]}'

libs/scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_actor_exists.py

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -37,8 +37,9 @@ class GazeboActorExists(RunProcess):
3737
3838
"""
3939

40-
def __init__(self, entity_name: str, world_name: str):
40+
def __init__(self):
4141
super().__init__()
42+
self.entity_name = None
4243
self.current_state = ActorExistsActionState.IDLE
4344

4445
def execute(self, entity_name: str, world_name: str): # pylint: disable=arguments-differ

libs/scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_delete_actor.py

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -37,8 +37,9 @@ class GazeboDeleteActor(RunProcess):
3737
3838
"""
3939

40-
def __init__(self, associated_actor, entity_name: str, world_name: str):
40+
def __init__(self, associated_actor):
4141
super().__init__()
42+
self.entity_name = None
4243
self.current_state = DeleteActionState.IDLE
4344

4445
def execute(self, associated_actor, entity_name: str, world_name: str): # pylint: disable=arguments-differ

libs/scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_relative_spawn_actor.py

Lines changed: 7 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -30,20 +30,17 @@ class GazeboRelativeSpawnActor(GazeboSpawnActor):
3030
3131
"""
3232

33-
def __init__(self, associated_actor,
34-
frame_id: str, parent_frame_id: str,
35-
distance: float, world_name: str, xacro_arguments: list,
36-
model: str):
37-
super().__init__(associated_actor, None, world_name, xacro_arguments, model)
33+
def __init__(self, associated_actor, xacro_arguments: list, model: str):
34+
super().__init__(associated_actor, xacro_arguments, model)
3835
self._pose = '{}'
36+
self.model = model
37+
self.world_name = None
38+
self.xacro_arguments = xacro_arguments
3939
self.tf_buffer = Buffer()
4040
self.tf_listener = None
4141

42-
def execute(self, associated_actor, # pylint: disable=arguments-differ
43-
frame_id: str, parent_frame_id: str,
44-
distance: float, world_name: str, xacro_arguments: list,
45-
model: str):
46-
super().execute(associated_actor, None, world_name, xacro_arguments, model)
42+
def execute(self, associated_actor, frame_id: str, parent_frame_id: str, distance: float, world_name: str): # pylint: disable=arguments-differ
43+
super().execute(associated_actor, None, world_name)
4744
self.frame_id = frame_id
4845
self.parent_frame_id = parent_frame_id
4946
self.distance = distance

libs/scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_spawn_actor.py

Lines changed: 2 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,7 @@ class GazeboSpawnActor(RunProcess):
4545
4646
"""
4747

48-
def __init__(self, associated_actor, spawn_pose: list, world_name: str, xacro_arguments: list, model: str):
48+
def __init__(self, associated_actor, xacro_arguments: list, model: str):
4949
"""
5050
init
5151
"""
@@ -92,9 +92,7 @@ def setup(self, **kwargs):
9292
raise ActionError(f'Invalid model specified ({self.entity_model})', action=self)
9393
self.current_state = SpawnActionState.MODEL_AVAILABLE
9494

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

libs/scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_wait_for_sim.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -35,7 +35,7 @@ class GazeboWaitForSim(RunProcess):
3535
Class to wait for the simulation to become active
3636
"""
3737

38-
def __init__(self, world_name: str, timeout: int):
38+
def __init__(self):
3939
super().__init__()
4040
self.current_state = WaitForSimulationActionState.IDLE
4141

libs/scenario_execution_kubernetes/scenario_execution_kubernetes/kubernetes_base_action.py

Lines changed: 3 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -29,9 +29,9 @@ class KubernetesBaseActionState(Enum):
2929

3030
class KubernetesBaseAction(BaseAction):
3131

32-
def __init__(self, namespace: str, within_cluster: bool):
32+
def __init__(self, within_cluster: bool):
3333
super().__init__()
34-
self.namespace = namespace
34+
self.namespace = None
3535
self.within_cluster = within_cluster
3636
self.client = None
3737
self.current_state = KubernetesBaseActionState.IDLE
@@ -44,10 +44,8 @@ def setup(self, **kwargs):
4444
config.load_kube_config()
4545
self.client = client.CoreV1Api()
4646

47-
def execute(self, namespace: str, within_cluster: bool):
47+
def execute(self, namespace: str):
4848
self.namespace = namespace
49-
if within_cluster != self.within_cluster:
50-
raise ValueError("parameter 'within_cluster' is not allowed to change since initialization.")
5149

5250
def update(self) -> py_trees.common.Status: # pylint: disable=too-many-return-statements
5351
if self.current_state == KubernetesBaseActionState.IDLE:

0 commit comments

Comments
 (0)