diff --git a/docs/development.rst b/docs/development.rst index 478254aa..f88889fd 100644 --- a/docs/development.rst +++ b/docs/development.rst @@ -95,6 +95,9 @@ Implement an Action - Make use of ``kwargs['logger']``, available in ``setup()`` - If you want to draw markers for RViz, use ``kwargs['marker_handler']``, available in ``setup()`` (with ROS backend) - Use arguments from ``__init__()`` for a longer running initialization in ``setup()`` and the arguments from ``execute()`` to set values just before executing the action. +- ``__init__()`` and ``setup()`` are called once, ``execute()`` might be called multiple times. +- 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. +- Arguments that need late resolving (e.g. referring to variables or external methods) need to be consumed in ``execute()``. - ``setup()`` provides several arguments that might be useful: - ``input_dir``: Directory containing the scenario file - ``output_dir``: If given on command-line, contains the directory to save output to diff --git a/docs/libraries.rst b/docs/libraries.rst index bdcaf422..82d4655c 100644 --- a/docs/libraries.rst +++ b/docs/libraries.rst @@ -437,10 +437,14 @@ Patch an existing Kubernetes network policy. - ``string`` - - The target network policy to patch - * - ``network_enabled`` + * - ``ingress_enabled`` - ``bool`` - - - Should the network be enabled + - Should ingress (i.e., incoming) network traffic be enabled + * - ``egress_enabled`` + - ``bool`` + - + - Should egress (i.e., outgoing) network traffic be enabled * - ``match_label`` - ``key_value`` - diff --git a/docs/tutorials.rst b/docs/tutorials.rst index c5d8e346..7633758c 100644 --- a/docs/tutorials.rst +++ b/docs/tutorials.rst @@ -91,7 +91,7 @@ Then, we can write the implementation of action plugin in Python. class CustomAction(BaseAction): - def __init__(self, data: str): + def __init__(self): super().__init__() def execute(self, data: str): @@ -105,9 +105,9 @@ Then, we can write the implementation of action plugin in Python. In the example, we created a custom action plugin to print a message on the screen. The first step is to create an action implementation, based on the class ``BaseAction``. There are two methods that can be overloaded in order to receive the action arguments as defined in the osc file. -The first is the ``__init__()`` function which gets the argument values as they get initialized during parsing the scenario file. -The second is the ``execute()`` function which gets the argument values as they are currently defined at the time the action gets executed. -This allows to initialize the action and then set the latest values just before the action gets triggered. + +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. +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). The action plugin ``custom_action`` only defines one parameter ``data``, so the behavior only has to accept ``data`` as an argument. Then, override the ``update()`` function to define how the diff --git a/examples/example_library/example_library/actions/custom_action.py b/examples/example_library/example_library/actions/custom_action.py index 639a73f2..c7a2d6f3 100644 --- a/examples/example_library/example_library/actions/custom_action.py +++ b/examples/example_library/example_library/actions/custom_action.py @@ -21,7 +21,7 @@ class CustomAction(BaseAction): - def __init__(self, data: str): # get action arguments, at the time of initialization + def __init__(self): # get action arguments, at the time of initialization super().__init__() def execute(self, data: str): # get action arguments, at the time of execution (may got updated during scenario execution) diff --git a/libs/scenario_execution_floorplan_dsl/scenario_execution_floorplan_dsl/actions/generate_floorplan.py b/libs/scenario_execution_floorplan_dsl/scenario_execution_floorplan_dsl/actions/generate_floorplan.py index 5cb9df93..863e7f2c 100644 --- a/libs/scenario_execution_floorplan_dsl/scenario_execution_floorplan_dsl/actions/generate_floorplan.py +++ b/libs/scenario_execution_floorplan_dsl/scenario_execution_floorplan_dsl/actions/generate_floorplan.py @@ -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 @@ -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: diff --git a/libs/scenario_execution_floorplan_dsl/scenario_execution_floorplan_dsl/actions/generate_gazebo_world.py b/libs/scenario_execution_floorplan_dsl/scenario_execution_floorplan_dsl/actions/generate_gazebo_world.py index c0be2116..1cee1c84 100644 --- a/libs/scenario_execution_floorplan_dsl/scenario_execution_floorplan_dsl/actions/generate_gazebo_world.py +++ b/libs/scenario_execution_floorplan_dsl/scenario_execution_floorplan_dsl/actions/generate_gazebo_world.py @@ -17,32 +17,32 @@ 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 class GenerateGazeboWorld(BaseAction): - def __init__(self, associated_actor, sdf_template: str, arguments: list): + def __init__(self, associated_actor, sdf_template: str): super().__init__() self.sdf_template = sdf_template self.spawn_utils = SpawnUtils(self.logger) 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): + def execute(self, associated_actor, arguments: list): self.arguments_string = "" for elem in arguments: self.arguments_string += f'{elem["key"]}:={elem["value"]}' diff --git a/libs/scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_actor_exists.py b/libs/scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_actor_exists.py index e905eda4..1897ba56 100644 --- a/libs/scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_actor_exists.py +++ b/libs/scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_actor_exists.py @@ -37,8 +37,9 @@ class GazeboActorExists(RunProcess): """ - def __init__(self, entity_name: str, world_name: str): + def __init__(self): super().__init__() + self.entity_name = None self.current_state = ActorExistsActionState.IDLE def execute(self, entity_name: str, world_name: str): # pylint: disable=arguments-differ diff --git a/libs/scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_delete_actor.py b/libs/scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_delete_actor.py index c86b1105..7237849f 100644 --- a/libs/scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_delete_actor.py +++ b/libs/scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_delete_actor.py @@ -37,8 +37,9 @@ class GazeboDeleteActor(RunProcess): """ - def __init__(self, associated_actor, entity_name: str, world_name: str): + def __init__(self, associated_actor): super().__init__() + self.entity_name = None self.current_state = DeleteActionState.IDLE def execute(self, associated_actor, entity_name: str, world_name: str): # pylint: disable=arguments-differ diff --git a/libs/scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_relative_spawn_actor.py b/libs/scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_relative_spawn_actor.py index d3da21d4..c31419a7 100644 --- a/libs/scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_relative_spawn_actor.py +++ b/libs/scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_relative_spawn_actor.py @@ -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): @@ -29,20 +30,17 @@ class GazeboRelativeSpawnActor(GazeboSpawnActor): """ - def __init__(self, associated_actor, - frame_id: str, parent_frame_id: str, - distance: float, world_name: str, xacro_arguments: list, - model: str): - super().__init__(associated_actor, None, world_name, xacro_arguments, model) + def __init__(self, associated_actor, xacro_arguments: list, model: str): + super().__init__(associated_actor, xacro_arguments, model) self._pose = '{}' + self.model = model + self.world_name = None + self.xacro_arguments = xacro_arguments self.tf_buffer = Buffer() self.tf_listener = None - def execute(self, associated_actor, # pylint: disable=arguments-differ - frame_id: str, parent_frame_id: str, - distance: float, world_name: str, xacro_arguments: list, - model: str): - super().execute(associated_actor, None, world_name, xacro_arguments, model) + def execute(self, associated_actor, frame_id: str, parent_frame_id: str, distance: float, world_name: str): # pylint: disable=arguments-differ + super().execute(associated_actor, None, world_name) self.frame_id = frame_id self.parent_frame_id = parent_frame_id self.distance = distance @@ -97,4 +95,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 diff --git a/libs/scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_spawn_actor.py b/libs/scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_spawn_actor.py index 2d8fe1dc..a98f4f9a 100644 --- a/libs/scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_spawn_actor.py +++ b/libs/scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_spawn_actor.py @@ -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 @@ -44,7 +45,7 @@ class GazeboSpawnActor(RunProcess): """ - def __init__(self, associated_actor, spawn_pose: list, world_name: str, xacro_arguments: list, model: str): + def __init__(self, associated_actor, xacro_arguments: list, model: str): """ init """ @@ -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) @@ -88,12 +89,10 @@ 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.") + def execute(self, associated_actor, spawn_pose: list, world_name: str): # pylint: disable=arguments-differ self.spawn_pose = spawn_pose self.world_name = world_name @@ -175,7 +174,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): diff --git a/libs/scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_wait_for_sim.py b/libs/scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_wait_for_sim.py index 82e2d0a8..c9d1a584 100644 --- a/libs/scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_wait_for_sim.py +++ b/libs/scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_wait_for_sim.py @@ -35,7 +35,7 @@ class GazeboWaitForSim(RunProcess): Class to wait for the simulation to become active """ - def __init__(self, world_name: str, timeout: int): + def __init__(self): super().__init__() self.current_state = WaitForSimulationActionState.IDLE diff --git a/libs/scenario_execution_kubernetes/scenario_execution_kubernetes/kubernetes_base_action.py b/libs/scenario_execution_kubernetes/scenario_execution_kubernetes/kubernetes_base_action.py index 6c45509d..622c07fa 100644 --- a/libs/scenario_execution_kubernetes/scenario_execution_kubernetes/kubernetes_base_action.py +++ b/libs/scenario_execution_kubernetes/scenario_execution_kubernetes/kubernetes_base_action.py @@ -29,9 +29,9 @@ class KubernetesBaseActionState(Enum): class KubernetesBaseAction(BaseAction): - def __init__(self, namespace: str, within_cluster: bool): + def __init__(self, within_cluster: bool): super().__init__() - self.namespace = namespace + self.namespace = None self.within_cluster = within_cluster self.client = None self.current_state = KubernetesBaseActionState.IDLE @@ -44,10 +44,8 @@ def setup(self, **kwargs): config.load_kube_config() self.client = client.CoreV1Api() - def execute(self, namespace: str, within_cluster: bool): + def execute(self, namespace: str): self.namespace = namespace - if within_cluster != self.within_cluster: - raise ValueError("parameter 'within_cluster' is not allowed to change since initialization.") def update(self) -> py_trees.common.Status: # pylint: disable=too-many-return-statements if self.current_state == KubernetesBaseActionState.IDLE: diff --git a/libs/scenario_execution_kubernetes/scenario_execution_kubernetes/kubernetes_patch_network_policy.py b/libs/scenario_execution_kubernetes/scenario_execution_kubernetes/kubernetes_patch_network_policy.py index 4f8a98c6..e7282fef 100644 --- a/libs/scenario_execution_kubernetes/scenario_execution_kubernetes/kubernetes_patch_network_policy.py +++ b/libs/scenario_execution_kubernetes/scenario_execution_kubernetes/kubernetes_patch_network_policy.py @@ -29,11 +29,12 @@ class KubernetesPatchNetworkPolicyState(Enum): class KubernetesPatchNetworkPolicy(BaseAction): - def __init__(self, namespace: str, target: str, network_enabled: bool, match_label: tuple, within_cluster: bool): + def __init__(self, namespace: str, target: str, ingress_enabled: bool, egress_enabled: bool, match_label: tuple, within_cluster: bool): super().__init__() self.namespace = namespace self.target = target - self.network_enabled = network_enabled + self.ingress_enabled = ingress_enabled + self.egress_enabled = egress_enabled self.within_cluster = within_cluster if not isinstance(match_label, dict) or not "key" in match_label or not "value" in match_label: raise ValueError("match_label expected to be key-value pair.") @@ -53,7 +54,7 @@ def setup(self, **kwargs): def update(self) -> py_trees.common.Status: # pylint: disable=too-many-return-statements if self.current_state == KubernetesPatchNetworkPolicyState.IDLE: self.current_request = self.network_client.patch_namespaced_network_policy(self.target, body=self.get_network_policy( - policy_name=self.target, enable=self.network_enabled, match_label=self.match_label), namespace=self.namespace, async_req=True) + policy_name=self.target, enable_ingress=self.ingress_enabled, enable_egress=self.egress_enabled, match_label=self.match_label), namespace=self.namespace, async_req=True) self.current_state = KubernetesPatchNetworkPolicyState.REQUEST_SENT self.feedback_message = f"Requested patching '{self.target}' in namespace '{self.namespace}'" # pylint: disable= attribute-defined-outside-init return py_trees.common.Status.RUNNING @@ -76,14 +77,16 @@ def update(self) -> py_trees.common.Status: # pylint: disable=too-many-return-s return py_trees.common.Status.FAILURE return py_trees.common.Status.FAILURE - def get_network_policy(self, policy_name, match_label, enable): + def get_network_policy(self, policy_name, match_label, enable_ingress, enable_egress): body = client.V1NetworkPolicy() body.metadata = client.V1ObjectMeta(name=f"{policy_name}") body.spec = client.V1NetworkPolicySpec(pod_selector=client.V1LabelSelector(match_labels={match_label["key"]: match_label["value"]})) - if enable: - body.spec.egress = [client.V1NetworkPolicyEgressRule()] + if enable_ingress: body.spec.ingress = [client.V1NetworkPolicyIngressRule()] else: - body.spec.egress = [] body.spec.ingress = [] + if enable_egress: + body.spec.egress = [client.V1NetworkPolicyEgressRule()] + else: + body.spec.egress = [] return body diff --git a/libs/scenario_execution_kubernetes/scenario_execution_kubernetes/kubernetes_patch_pod.py b/libs/scenario_execution_kubernetes/scenario_execution_kubernetes/kubernetes_patch_pod.py index 33ee2a84..c96db161 100644 --- a/libs/scenario_execution_kubernetes/scenario_execution_kubernetes/kubernetes_patch_pod.py +++ b/libs/scenario_execution_kubernetes/scenario_execution_kubernetes/kubernetes_patch_pod.py @@ -20,13 +20,14 @@ class KubernetesPatchPod(KubernetesBaseAction): - def __init__(self, namespace: str, target: str, body: str, within_cluster: bool): - super().__init__(namespace, within_cluster) - self.target = target + def __init__(self, within_cluster: bool): + super().__init__(within_cluster) + self.namespace = None + self.target = None self.body = None - def execute(self, namespace: str, target: str, body: str, within_cluster: bool): # pylint: disable=arguments-differ - super().execute(namespace, within_cluster) + def execute(self, namespace: str, target: str, body: str): # pylint: disable=arguments-differ + super().execute(namespace) self.target = target trimmed_data = body.encode('utf-8').decode('unicode_escape') try: diff --git a/libs/scenario_execution_kubernetes/scenario_execution_kubernetes/kubernetes_pod_exec.py b/libs/scenario_execution_kubernetes/scenario_execution_kubernetes/kubernetes_pod_exec.py index 8df6f3ae..a834590e 100644 --- a/libs/scenario_execution_kubernetes/scenario_execution_kubernetes/kubernetes_pod_exec.py +++ b/libs/scenario_execution_kubernetes/scenario_execution_kubernetes/kubernetes_pod_exec.py @@ -33,12 +33,12 @@ class KubernetesPodExecState(Enum): class KubernetesPodExec(BaseAction): - def __init__(self, target: str, command: list, regex: bool, namespace: str, within_cluster: bool): + def __init__(self, within_cluster: bool): super().__init__() - self.target = target - self.namespace = namespace - self.regex = regex - self.command = command + self.target = None + self.namespace = None + self.regex = None + self.command = None self.within_cluster = within_cluster self.client = None self.reponse_queue = queue.Queue() @@ -56,9 +56,7 @@ def setup(self, **kwargs): self.exec_thread = threading.Thread(target=self.pod_exec, daemon=True) - def execute(self, target: str, command: list, regex: bool, namespace: str, within_cluster: bool): - if within_cluster != self.within_cluster: - raise ValueError("parameter 'within_cluster' is not allowed to change since initialization.") + def execute(self, target: str, command: list, regex: bool, namespace: str): self.target = target self.namespace = namespace self.command = command diff --git a/libs/scenario_execution_kubernetes/scenario_execution_kubernetes/kubernetes_wait_for_network_policy_status.py b/libs/scenario_execution_kubernetes/scenario_execution_kubernetes/kubernetes_wait_for_network_policy_status.py index c4d26ab8..0b9c3486 100644 --- a/libs/scenario_execution_kubernetes/scenario_execution_kubernetes/kubernetes_wait_for_network_policy_status.py +++ b/libs/scenario_execution_kubernetes/scenario_execution_kubernetes/kubernetes_wait_for_network_policy_status.py @@ -43,7 +43,7 @@ def setup(self, **kwargs): self.k8s_client = client.api_client.ApiClient() self.network_client = client.NetworkingV1Api(self.k8s_client) - def execute(self, target: str, status: tuple, namespace: str, within_cluster: bool): + def execute(self): self.monitoring_thread = threading.Thread(target=self.watch_network, daemon=True) self.monitoring_thread.start() diff --git a/libs/scenario_execution_kubernetes/scenario_execution_kubernetes/kubernetes_wait_for_pod_status.py b/libs/scenario_execution_kubernetes/scenario_execution_kubernetes/kubernetes_wait_for_pod_status.py index 5551ea73..9a51e51c 100644 --- a/libs/scenario_execution_kubernetes/scenario_execution_kubernetes/kubernetes_wait_for_pod_status.py +++ b/libs/scenario_execution_kubernetes/scenario_execution_kubernetes/kubernetes_wait_for_pod_status.py @@ -32,15 +32,13 @@ class KubernetesWaitForPodStatusState(Enum): class KubernetesWaitForPodStatus(BaseAction): - def __init__(self, target: str, regex: bool, status: tuple, namespace: str, within_cluster: bool): + def __init__(self, within_cluster: bool): super().__init__() - self.target = target - self.namespace = namespace - if not isinstance(status, tuple) or not isinstance(status[0], str): - raise ValueError("Status expected to be enum.") - self.expected_status = status[0] + self.target = None + self.namespace = None + self.expected_status = None self.within_cluster = within_cluster - self.regex = regex + self.regex = None self.client = None self.update_queue = queue.Queue() self.current_state = KubernetesWaitForPodStatusState.IDLE @@ -55,11 +53,12 @@ def setup(self, **kwargs): self.monitoring_thread = threading.Thread(target=self.watch_pods, daemon=True) self.monitoring_thread.start() - def execute(self, target: str, regex: bool, status: tuple, namespace: str, within_cluster: bool): + def execute(self, target: str, regex: bool, status: tuple, namespace: str): self.target = target self.namespace = namespace + if not isinstance(status, tuple) or not isinstance(status[0], str): + raise ValueError("Status expected to be enum.") self.expected_status = status[0] - self.within_cluster = within_cluster self.regex = regex self.current_state = KubernetesWaitForPodStatusState.MONITORING diff --git a/libs/scenario_execution_kubernetes/scenario_execution_kubernetes/lib_osc/kubernetes.osc b/libs/scenario_execution_kubernetes/scenario_execution_kubernetes/lib_osc/kubernetes.osc index 170a5385..76224aed 100644 --- a/libs/scenario_execution_kubernetes/scenario_execution_kubernetes/lib_osc/kubernetes.osc +++ b/libs/scenario_execution_kubernetes/scenario_execution_kubernetes/lib_osc/kubernetes.osc @@ -36,7 +36,8 @@ action kubernetes_delete inherits kubernetes_base_action: action kubernetes_patch_network_policy inherits kubernetes_base_action: # patch an existing network policy target: string # network-policy to patch - network_enabled: bool # should the network be enabled? + ingress_enabled: bool # should incoming network traffic be enabled? + egress_enabled: bool # should outgoing network traffic be enabled? match_label: key_value action kubernetes_patch_pod inherits kubernetes_base_action: diff --git a/libs/scenario_execution_kubernetes/scenarios/test_kubernetes_create_delete.osc b/libs/scenario_execution_kubernetes/scenarios/test_kubernetes_create_delete.osc index 7f98de05..f13f3448 100644 --- a/libs/scenario_execution_kubernetes/scenarios/test_kubernetes_create_delete.osc +++ b/libs/scenario_execution_kubernetes/scenarios/test_kubernetes_create_delete.osc @@ -8,6 +8,6 @@ scenario test_kubernetes_create_from_yaml: kubernetes_create_from_yaml(yaml_file: "test.yaml") kubernetes_wait_for_pod_status(target: "test", status: kubernetes_pod_status!running) #kubernetes_wait_for_network_policy_status("test-network-policy", kubernetes_network_policy_status!added) - kubernetes_patch_network_policy(target: "test-network-policy", network_enabled: false, match_label: key_value("app", "foo")) - kubernetes_patch_network_policy(target: "test-network-policy", network_enabled: true, match_label: key_value("app", "foo")) + kubernetes_patch_network_policy(target: "test-network-policy", ingress_enabled: false, egress_enabled: false, match_label: key_value("app", "foo")) + kubernetes_patch_network_policy(target: "test-network-policy", ingress_enabled: true, egress_enabled: true, match_label: key_value("app", "foo")) kubernetes_delete(target: "test", element_type: kubernetes_element_type!pod) diff --git a/libs/scenario_execution_nav2/scenario_execution_nav2/actions/init_nav2.py b/libs/scenario_execution_nav2/scenario_execution_nav2/actions/init_nav2.py index 7c27c851..26674f4d 100644 --- a/libs/scenario_execution_nav2/scenario_execution_nav2/actions/init_nav2.py +++ b/libs/scenario_execution_nav2/scenario_execution_nav2/actions/init_nav2.py @@ -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): @@ -58,12 +58,12 @@ class InitNav2(BaseAction): """ - def __init__(self, associated_actor, initial_pose: list, base_frame_id: str, wait_for_initial_pose: bool, use_initial_pose: bool, namespace_override: str): + def __init__(self, associated_actor, namespace_override: str): super().__init__() - self.initial_pose = initial_pose - self.base_frame_id = base_frame_id - self.wait_for_initial_pose = wait_for_initial_pose - self.use_initial_pose = use_initial_pose + self.initial_pose = None + self.base_frame_id = None + self.wait_for_initial_pose = None + self.use_initial_pose = None self.namespace = associated_actor["namespace"] self.node = None self.future = None @@ -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( @@ -118,14 +118,12 @@ def setup(self, **kwargs): amcl_pose_qos, callback_group=ReentrantCallbackGroup()) - def execute(self, associated_actor, initial_pose: list, base_frame_id: str, wait_for_initial_pose: bool, use_initial_pose: bool, namespace_override: str): + def execute(self, associated_actor, initial_pose: list, base_frame_id: str, wait_for_initial_pose: bool, use_initial_pose: bool): self.initial_pose = initial_pose self.base_frame_id = base_frame_id self.wait_for_initial_pose = wait_for_initial_pose self.use_initial_pose = use_initial_pose self.namespace = associated_actor["namespace"] - if namespace_override: - self.namespace = namespace_override def update(self) -> py_trees.common.Status: """ diff --git a/libs/scenario_execution_nav2/scenario_execution_nav2/actions/nav_through_poses.py b/libs/scenario_execution_nav2/scenario_execution_nav2/actions/nav_through_poses.py index 8312006f..64989c30 100644 --- a/libs/scenario_execution_nav2/scenario_execution_nav2/actions/nav_through_poses.py +++ b/libs/scenario_execution_nav2/scenario_execution_nav2/actions/nav_through_poses.py @@ -25,19 +25,16 @@ class NavThroughPoses(RosActionCall): Class to navigate through poses """ - def __init__(self, associated_actor, goal_poses: list, action_topic: str, namespace_override: str): + def __init__(self, associated_actor, action_topic: str, namespace_override: str): self.namespace = associated_actor["namespace"] if namespace_override: self.namespace = namespace_override self.goal_poses = None - super().__init__(self.namespace + '/' + action_topic, "nav2_msgs.action.NavigateThroughPoses", "") + super().__init__(self.namespace + '/' + action_topic, "nav2_msgs.action.NavigateThroughPoses") - def execute(self, associated_actor, goal_poses: list, action_topic: str, namespace_override: str) -> None: # pylint: disable=arguments-differ,arguments-renamed - self.namespace = associated_actor["namespace"] - if namespace_override: - self.namespace = namespace_override + def execute(self, associated_actor, goal_poses: list) -> None: # pylint: disable=arguments-differ,arguments-renamed self.goal_poses = goal_poses - super().execute(self.namespace + '/' + action_topic, "nav2_msgs.action.NavigateThroughPoses", "") + super().execute("") def get_goal_msg(self): goal_msg = NavigateThroughPoses.Goal() diff --git a/libs/scenario_execution_nav2/scenario_execution_nav2/actions/nav_to_pose.py b/libs/scenario_execution_nav2/scenario_execution_nav2/actions/nav_to_pose.py index 755198f2..c79f9cf8 100644 --- a/libs/scenario_execution_nav2/scenario_execution_nav2/actions/nav_to_pose.py +++ b/libs/scenario_execution_nav2/scenario_execution_nav2/actions/nav_to_pose.py @@ -26,19 +26,16 @@ class NavToPose(RosActionCall): Class to navigate to a pose """ - def __init__(self, associated_actor, goal_pose: list, action_topic: str, namespace_override: str) -> None: + def __init__(self, associated_actor, action_topic: str, namespace_override: str) -> None: self.namespace = associated_actor["namespace"] if namespace_override: self.namespace = namespace_override self.goal_pose = None - super().__init__(self.namespace + '/' + action_topic, "nav2_msgs.action.NavigateToPose", "") + super().__init__(self.namespace + '/' + action_topic, "nav2_msgs.action.NavigateToPose") - def execute(self, associated_actor, goal_pose: list, action_topic: str, namespace_override: str) -> None: # pylint: disable=arguments-differ,arguments-renamed - self.namespace = associated_actor["namespace"] - if namespace_override: - self.namespace = namespace_override + def execute(self, associated_actor, goal_pose: list) -> None: # pylint: disable=arguments-differ,arguments-renamed self.goal_pose = goal_pose - super().execute(self.namespace + '/' + action_topic, "nav2_msgs.action.NavigateToPose", "") + super().execute("") def get_goal_msg(self): goal_msg = NavigateToPose.Goal() diff --git a/libs/scenario_execution_pybullet/scenario_execution_pybullet/actions/actor_distance_traveled.py b/libs/scenario_execution_pybullet/scenario_execution_pybullet/actions/actor_distance_traveled.py index d3b9d018..d812fdc9 100644 --- a/libs/scenario_execution_pybullet/scenario_execution_pybullet/actions/actor_distance_traveled.py +++ b/libs/scenario_execution_pybullet/scenario_execution_pybullet/actions/actor_distance_traveled.py @@ -22,7 +22,7 @@ class ActorDistanceTraveled(BaseAction): - def __init__(self): + def __init__(self, associated_actor): super().__init__() self.sim_steps_per_tick = None self.distance_traveled = None diff --git a/libs/scenario_execution_pybullet/scenario_execution_pybullet/actions/actor_set_joint_motor_control.py b/libs/scenario_execution_pybullet/scenario_execution_pybullet/actions/actor_set_joint_motor_control.py index 6c332284..1bf5e025 100644 --- a/libs/scenario_execution_pybullet/scenario_execution_pybullet/actions/actor_set_joint_motor_control.py +++ b/libs/scenario_execution_pybullet/scenario_execution_pybullet/actions/actor_set_joint_motor_control.py @@ -21,7 +21,7 @@ class ActorSetJointMotorControl(BaseAction): - def __init__(self): + def __init__(self, associated_actor): super().__init__() self.target_velocity = None self.force = None diff --git a/libs/scenario_execution_pybullet/scenario_execution_pybullet/actions/actor_spawn.py b/libs/scenario_execution_pybullet/scenario_execution_pybullet/actions/actor_spawn.py index 0b0d8d28..53422747 100644 --- a/libs/scenario_execution_pybullet/scenario_execution_pybullet/actions/actor_spawn.py +++ b/libs/scenario_execution_pybullet/scenario_execution_pybullet/actions/actor_spawn.py @@ -21,7 +21,7 @@ class ActorSpawn(BaseAction): - def __init__(self): + def __init__(self, associated_actor): super().__init__() self.spawn_pose = None self.model = None diff --git a/libs/scenario_execution_pybullet/scenario_execution_pybullet/actions/sim_initialize.py b/libs/scenario_execution_pybullet/scenario_execution_pybullet/actions/sim_initialize.py index 4b60d153..8f02d136 100644 --- a/libs/scenario_execution_pybullet/scenario_execution_pybullet/actions/sim_initialize.py +++ b/libs/scenario_execution_pybullet/scenario_execution_pybullet/actions/sim_initialize.py @@ -22,7 +22,7 @@ class SimInitialize(BaseAction): - def __init__(self): + def __init__(self, associated_actor): super().__init__() self.world = None diff --git a/libs/scenario_execution_pybullet/scenario_execution_pybullet/actions/sim_run.py b/libs/scenario_execution_pybullet/scenario_execution_pybullet/actions/sim_run.py index c4ba4688..503a726c 100644 --- a/libs/scenario_execution_pybullet/scenario_execution_pybullet/actions/sim_run.py +++ b/libs/scenario_execution_pybullet/scenario_execution_pybullet/actions/sim_run.py @@ -15,14 +15,14 @@ # 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 class SimRun(BaseAction): - def __init__(self): + def __init__(self, associated_actor): super().__init__() self.sim_steps_per_tick = 0 @@ -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.") diff --git a/libs/scenario_execution_x11/scenario_execution_x11/actions/capture_screen.py b/libs/scenario_execution_x11/scenario_execution_x11/actions/capture_screen.py index 432c49aa..92bf8994 100644 --- a/libs/scenario_execution_x11/scenario_execution_x11/actions/capture_screen.py +++ b/libs/scenario_execution_x11/scenario_execution_x11/actions/capture_screen.py @@ -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 @@ -29,22 +30,23 @@ class CaptureScreenState(Enum): class CaptureScreen(RunProcess): - def __init__(self, output_filename: str, frame_rate: float): - super().__init__("", wait_for_shutdown=True) + def __init__(self): + super().__init__() self.current_state = None self.output_dir = "." 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 + super().execute(None, wait_for_shutdown=True) self.current_state = CaptureScreenState.IDLE cmd = ["ffmpeg", "-f", "x11grab", diff --git a/scenario_execution/scenario_execution/actions/base_action.py b/scenario_execution/scenario_execution/actions/base_action.py index c4e254fb..164b68e7 100644 --- a/scenario_execution/scenario_execution/actions/base_action.py +++ b/scenario_execution/scenario_execution/actions/base_action.py @@ -16,11 +16,13 @@ import py_trees from scenario_execution.model.types import ParameterDeclaration, ScenarioDeclaration +from scenario_execution.model.error import OSC2Error +import inspect class BaseAction(py_trees.behaviour.Behaviour): - # subclasses might implement __init__() with the same arguments as defined in osc + # subclasses might implement __init__() with osc2 arguments as required # CAUTION: __init__() only gets the initial parameter values. In case variables get modified during scenario execution, # the latest values are available in execute() only. def __init__(self, resolve_variable_reference_arguments_in_execute=True): @@ -28,9 +30,16 @@ def __init__(self, resolve_variable_reference_arguments_in_execute=True): self.logger = None self.blackboard = None self.resolve_variable_reference_arguments_in_execute = resolve_variable_reference_arguments_in_execute + + execute_method = getattr(self, "execute", None) + if execute_method is not None and callable(execute_method): + self.execute_method = execute_method + self.execute_skip_args = inspect.getfullargspec(getattr(self, "__init__", None)).args + else: + self.execute_method = None super().__init__(self.__class__.__name__) - # Subclasses might implement execute() with the same arguments as defined in osc. + # Subclasses might implement execute() with the osc2 arguments that are not used within __init__(). # def execute(self): # Subclasses might override shutdown() in order to cleanup on scenario shutdown. @@ -42,13 +51,12 @@ def shutdown(self): ############# def initialise(self): - execute_method = getattr(self, "execute", None) - if execute_method is not None and callable(execute_method): - + if self.execute_method is not None: if self.resolve_variable_reference_arguments_in_execute: - final_args = self._model.get_resolved_value(self.get_blackboard_client()) + final_args = self._model.get_resolved_value(self.get_blackboard_client(), skip_keys=self.execute_skip_args) else: - final_args = self._model.get_resolved_value_with_variable_references(self.get_blackboard_client()) + final_args = self._model.get_resolved_value_with_variable_references( + self.get_blackboard_client(), skip_keys=self.execute_skip_args) if self._model.actor: final_args["associated_actor"] = self._model.actor.get_resolved_value(self.get_blackboard_client()) @@ -78,7 +86,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 @@ -94,3 +102,11 @@ def get_associated_actor_variable(self, variable_name): model_blackboard_name = self.register_access_to_associated_actor_variable(variable_name) self.logger.debug(f"Get variable '{model_blackboard_name}'") return getattr(self.get_blackboard_client(), model_blackboard_name) + + +class ActionError(OSC2Error): + + def __init__(self, msg: str, action: BaseAction, *args) -> None: + if action is not None: + ctx = action._model.get_ctx() + super().__init__(msg, ctx, *args) diff --git a/scenario_execution/scenario_execution/actions/log.py b/scenario_execution/scenario_execution/actions/log.py index b57d6d1a..4cc77f66 100644 --- a/scenario_execution/scenario_execution/actions/log.py +++ b/scenario_execution/scenario_execution/actions/log.py @@ -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): @@ -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 diff --git a/scenario_execution/scenario_execution/actions/run_process.py b/scenario_execution/scenario_execution/actions/run_process.py index e0f4d8ef..9e753471 100644 --- a/scenario_execution/scenario_execution/actions/run_process.py +++ b/scenario_execution/scenario_execution/actions/run_process.py @@ -27,12 +27,12 @@ class RunProcess(BaseAction): Class to execute an process. """ - def __init__(self, command=None, wait_for_shutdown=True, shutdown_timeout=10, shutdown_signal=("", signal.SIGTERM)): + def __init__(self): super().__init__() - self.command = command.split(" ") if isinstance(command, str) else command - self.wait_for_shutdown = wait_for_shutdown - self.shutdown_timeout = shutdown_timeout - self.shutdown_signal = shutdown_signal[1] + self.command = None + self.wait_for_shutdown = None + self.shutdown_timeout = None + self.shutdown_signal = None self.executed = False self.process = None self.log_stdout_thread = None diff --git a/scenario_execution/scenario_execution/model/error.py b/scenario_execution/scenario_execution/model/error.py index 6c64d4bb..8d1c076f 100644 --- a/scenario_execution/scenario_execution/model/error.py +++ b/scenario_execution/scenario_execution/model/error.py @@ -18,24 +18,36 @@ from antlr4 import ParserRuleContext -class OSC2ParsingError(Exception): - """ - Error class for OSC2 parser - """ +class OSC2Error(Exception): def __init__(self, msg: str, context, *args) -> None: super().__init__(*args) self.msg = msg if isinstance(context, ParserRuleContext): - self.line = context.start.line - self.column = context.start.column - self.context = context.getText() - self.filename = "" + self.osc_ctx = (context.start.line, context.start.column, context.getText(), "") else: - self.line = context[0] - self.column = context[1] - self.context = context[2] - self.filename = context[3] + self.osc_ctx = context def __str__(self) -> str: - return self.msg + error_str = "" + if self.osc_ctx is not None: + if len(self.osc_ctx) == 4: + context = self.osc_ctx[2].replace('\n', '') + error_str = f"(line: {self.osc_ctx[0]}, column: {self.osc_ctx[1]} in '{self.osc_ctx[3]}') -> {context}: " + else: + error_str = f": " + error_str += self.msg + return error_str + + +class OSC2ParsingError(OSC2Error): + """ + Error class for OSC2 parser + """ + + def __init__(self, msg: str, context, *args) -> None: + if isinstance(context, ParserRuleContext): + ctx = (context.start.line, context.start.column, context.getText(), "") + else: + ctx = context + super().__init__(msg, ctx, *args) diff --git a/scenario_execution/scenario_execution/model/model_blackboard.py b/scenario_execution/scenario_execution/model/model_blackboard.py index d2456522..de59e7d3 100644 --- a/scenario_execution/scenario_execution/model/model_blackboard.py +++ b/scenario_execution/scenario_execution/model/model_blackboard.py @@ -26,8 +26,7 @@ def create_py_tree_blackboard(model, tree, logger, log_tree): try: model_blackboard.build(model, tree, log_tree) except OSC2ParsingError as e: - raise ValueError( - f'Error while creating py-tree:\nTraceback in "{e.filename}":\n -> {e.context}\n{e.__class__.__name__}: {e.msg}') from e + raise ValueError(f'Error while creating py-tree: {e}') from e class ModelToBlackboard(object): diff --git a/scenario_execution/scenario_execution/model/model_resolver.py b/scenario_execution/scenario_execution/model/model_resolver.py index 81118477..87ddfa81 100644 --- a/scenario_execution/scenario_execution/model/model_resolver.py +++ b/scenario_execution/scenario_execution/model/model_resolver.py @@ -29,8 +29,7 @@ def resolve_internal_model(model, tree, logger, log_tree): try: osc2scenario_resolver.visit(model) except OSC2ParsingError as e: - raise ValueError( - f'Error while creating tree:\nTraceback in "{e.filename}":\n -> {e.context}\n{e.__class__.__name__}: {e.msg}') from e + raise ValueError(f'Error while creating tree: {e}') from e if log_tree: logger.info("----Internal model (resolved)-----") diff --git a/scenario_execution/scenario_execution/model/model_to_py_tree.py b/scenario_execution/scenario_execution/model/model_to_py_tree.py index c7bb6ca8..dcc48281 100644 --- a/scenario_execution/scenario_execution/model/model_to_py_tree.py +++ b/scenario_execution/scenario_execution/model/model_to_py_tree.py @@ -31,8 +31,7 @@ def create_py_tree(model, tree, logger, log_tree): try: final_tree = model_to_py_tree.build(model, tree, log_tree) except OSC2ParsingError as e: - raise ValueError( - f'Error while creating py-tree:\nTraceback in "{e.filename}":\n -> {e.context}\n{e.__class__.__name__}: {e.msg}') from e + raise ValueError(f'Error while creating py-tree: {e}') from e return final_tree @@ -102,15 +101,15 @@ def update(self): return Status.SUCCESS -class ExpressionBehavior(py_trees.behaviour.Behaviour): - - def __init__(self, name: "ExpressionBehavior", expression: Expression): - super().__init__(name) +class ExpressionBehavior(BaseAction): # py_trees.behaviour.Behaviour): + def __init__(self, name: "ExpressionBehavior", expression: Expression, model, logger): + super().__init__() + self._set_base_properities(name, model, logger) self.expression = expression def update(self): - if self.expression.eval(): + if self.expression.eval(self.get_blackboard_client()): return Status.SUCCESS else: return Status.RUNNING @@ -208,21 +207,14 @@ def compare_method_arguments(self, method, expected_args, behavior_name, node): raise OSC2ParsingError( msg=f'Plugin {behavior_name} {method.__name__} method is missing argument "self".', context=node.get_ctx()) - unknown_args = [] + unexpected_args = [] missing_args = copy.copy(expected_args) for element in method_args: if element not in expected_args: - unknown_args.append(element) + unexpected_args.append(element) else: missing_args.remove(element) - error_string = "" - if missing_args: - error_string += "missing: " + ", ".join(missing_args) - if unknown_args: - if error_string: - error_string += ", " - error_string += "unknown: " + ", ".join(unknown_args) - return method_args, error_string + return method_args, unexpected_args, missing_args def create_decorator(self, node: ModifierDeclaration, resolved_values): available_modifiers = ["repeat", "inverter", "timeout", "retry", "failure_is_running", "failure_is_success", @@ -318,32 +310,46 @@ def visit_behavior_invocation(self, node: BehaviorInvocation): # if __init__() is defined, check parameters. Allowed: # - __init__(self) # - __init__(self, resolve_variable_reference_arguments_in_execute) - # - __init__(self, ) - init_args, error_string = self.compare_method_arguments(init_method, expected_args, behavior_name, node) + # - __init__(self, ) + init_args, unexpected_args, args_not_in_init = self.compare_method_arguments( + init_method, expected_args, behavior_name, node) if init_args != ["self"] and \ init_args != ["self", "resolve_variable_reference_arguments_in_execute"] and \ - set(init_args) != set(expected_args): + not all(x in expected_args for x in init_args): raise OSC2ParsingError( - msg=f'Plugin {behavior_name}: __init__() either only has "self" argument or all arguments defined in osc. {error_string}\n' + msg=f'Plugin {behavior_name}: __init__() either only has "self" argument and osc-defined arguments. Unexpected args: {", ".join(unexpected_args)}\n' f'expected definition with all arguments: {expected_args}', context=node.get_ctx() ) execute_method = getattr(behavior_cls, "execute", None) - if execute_method is not None: - _, error_string = self.compare_method_arguments(execute_method, expected_args, behavior_name, node) - if error_string: + if execute_method is None: + if args_not_in_init: raise OSC2ParsingError( - msg=f'Plugin {behavior_name}: execute() arguments differ from osc-definition: {error_string}.', context=node.get_ctx() - ) + msg=f'Plugin {behavior_name}: execute() required, but not defined. Required arguments (i.e. not defined in __init__()): {", ".join(args_not_in_init)}.', context=node.get_ctx()) + else: + expected_execute_args = copy.deepcopy(args_not_in_init) + expected_execute_args.append("self") + if node.actor: + expected_execute_args.append("associated_actor") + _, unexpected_execute_args, missing_execute_args = self.compare_method_arguments( + execute_method, expected_execute_args, behavior_name, node) + if missing_execute_args: + raise OSC2ParsingError( + msg=f'Plugin {behavior_name}: execute() is missing arguments: {", ".join(missing_execute_args)}. Either specify in __init__() or execute().', context=node.get_ctx()) + if unexpected_execute_args: + error = "" + if any(x in init_args for x in unexpected_execute_args): + error = " osc2 arguments, that are consumed in __init__() are not allowed to be used in execute() again. Please either remove argument(s) from __init__() or execute()." + raise OSC2ParsingError( + msg=f'Plugin {behavior_name}: execute() has unexpected arguments: {", ".join(unexpected_execute_args)}.{error}', context=node.get_ctx()) # initialize plugin instance action_name = node.name if not action_name: action_name = behavior_name - self.logger.debug( - f"Instantiate action '{action_name}', plugin '{behavior_name}'. with:\nExpected execute() arguments: {expected_args}") + self.logger.debug(f"Instantiate action '{action_name}', plugin '{behavior_name}'.") try: if init_args is not None and init_args != ['self'] and init_args != ['self', 'resolve_variable_reference_arguments_in_execute']: - final_args = node.get_resolved_value(self.blackboard) + final_args = node.get_resolved_value(self.blackboard, skip_keys=args_not_in_init) if node.actor: final_args["associated_actor"] = node.actor.get_resolved_value(self.blackboard) @@ -370,7 +376,7 @@ def visit_event_condition(self, node: EventCondition): expression = "" for child in node.get_children(): if isinstance(child, (RelationExpression, LogicalExpression)): - expression = ExpressionBehavior(name=node.get_ctx()[2], expression=self.visit(child)) + expression = ExpressionBehavior(name=node.get_ctx()[2], expression=self.visit(child), model=node, logger=self.logger) elif isinstance(child, ElapsedExpression): elapsed_condition = self.visit_elapsed_expression(child) expression = py_trees.timers.Timer(name=f"wait {elapsed_condition}s", duration=float(elapsed_condition)) diff --git a/scenario_execution/scenario_execution/model/osc2_parser.py b/scenario_execution/scenario_execution/model/osc2_parser.py index 94118ffb..1da88337 100644 --- a/scenario_execution/scenario_execution/model/osc2_parser.py +++ b/scenario_execution/scenario_execution/model/osc2_parser.py @@ -64,8 +64,7 @@ def load_internal_model(self, tree, file_name: str, log_model: bool = False, deb walker.walk(model_builder, tree) model = model_builder.get_model() except OSC2ParsingError as e: - raise ValueError( - f'Error creating internal model: Traceback in "{e.filename}":\n -> {e.context}\n{e.__class__.__name__}: {e.msg}') from e + raise ValueError(f'Error creating internal model: {e}') from e if log_model: self.logger.info("----Internal model-----") print_tree(model, self.logger) diff --git a/scenario_execution/scenario_execution/model/types.py b/scenario_execution/scenario_execution/model/types.py index 9903e826..599e2d60 100644 --- a/scenario_execution/scenario_execution/model/types.py +++ b/scenario_execution/scenario_execution/model/types.py @@ -394,7 +394,9 @@ def get_parameter_names(self): names.append(child.name) return list(set(names)) - def get_resolved_value(self, blackboard=None): + def get_resolved_value(self, blackboard=None, skip_keys=None): + if skip_keys is None: + skip_keys = [] params = {} # set values defined in base type @@ -406,6 +408,8 @@ def get_resolved_value(self, blackboard=None): param_keys = list(params.keys()) for child in self.get_children(): if isinstance(child, ParameterDeclaration): + if child.name in skip_keys: + continue # set from parameter param_type, _ = child.get_type() @@ -433,17 +437,22 @@ def get_resolved_value(self, blackboard=None): if named: raise OSC2ParsingError( msg=f'Positional argument after named argument not allowed.', context=child.get_ctx()) - params[param_keys[pos]] = child.get_resolved_value(blackboard) + if param_keys[pos] not in skip_keys: + params[param_keys[pos]] = child.get_resolved_value(blackboard) pos += 1 elif isinstance(child, NamedArgument): named = True - params[child.name] = child.get_resolved_value(blackboard) + if child.name not in skip_keys: + params[child.name] = child.get_resolved_value(blackboard) elif isinstance(child, KeepConstraintDeclaration): tmp = child.get_resolved_value(blackboard) merge_nested_dicts(params, tmp, key_must_exist=False) elif isinstance(child, MethodDeclaration): - params[child.name] = child.get_resolved_value(blackboard) - + if child.name not in skip_keys: + params[child.name] = child.get_resolved_value(blackboard) + for k in skip_keys: + if k in params: + del params[k] return params def get_type(self): @@ -1513,7 +1522,9 @@ def get_base_type(self): def get_type(self): return self.behavior, False - def get_resolved_value_with_variable_references(self, blackboard): + def get_resolved_value_with_variable_references(self, blackboard, skip_keys=None): + if skip_keys is None: + skip_keys = [] params = self.get_resolved_value(blackboard) pos = 0 @@ -1521,12 +1532,16 @@ def get_resolved_value_with_variable_references(self, blackboard): for child in self.get_children(): if isinstance(child, PositionalArgument): if isinstance(child.get_child(0), IdentifierReference): - params[param_keys[pos]] = child.get_child(0).get_blackboard_reference(blackboard) + if param_keys[pos] not in skip_keys: + params[param_keys[pos]] = child.get_child(0).get_blackboard_reference(blackboard) pos += 1 elif isinstance(child, NamedArgument): if isinstance(child.get_child(0), IdentifierReference): - params[child.name] = child.get_child(0).get_blackboard_reference(blackboard) - + if child.name not in skip_keys: + params[child.name] = child.get_child(0).get_blackboard_reference(blackboard) + for k in skip_keys: + if k in params: + del params[k] return params @@ -1836,7 +1851,7 @@ def get_type_string(self): return type_string def get_resolved_value(self, blackboard=None): - return visit_expression(self, blackboard).eval() + return visit_expression(self, blackboard).eval(blackboard) class UnaryExpression(ModelExpression): @@ -1904,7 +1919,7 @@ def get_type_string(self): return "bool" def get_resolved_value(self, blackboard=None): - return visit_expression(self, blackboard).eval() + return visit_expression(self, blackboard).eval(blackboard) class RelationExpression(ModelExpression): @@ -1931,7 +1946,7 @@ def get_type_string(self): return "bool" def get_resolved_value(self, blackboard=None): - return visit_expression(self, blackboard).eval() + return visit_expression(self, blackboard).eval(blackboard) class ListExpression(ModelExpression): @@ -2272,20 +2287,22 @@ def __init__(self, left, right, operator) -> None: self.right = right self.operator = operator - def resolve(self, param): + def resolve(self, param, blackboard): if isinstance(param, Expression): - return param.eval() + return param.eval(blackboard) elif isinstance(param, VariableReference): return param.get_value() + elif isinstance(param, FunctionApplicationExpression): + return param.get_resolved_value(blackboard) else: return param - def eval(self): - left = self.resolve(self.left) + def eval(self, blackboard): + left = self.resolve(self.left, blackboard) if self.right is None: return self.operator(left) else: - right = self.resolve(self.right) + right = self.resolve(self.right, blackboard) return self.operator(left, right) @@ -2339,6 +2356,8 @@ def visit_expression(node, blackboard): args[idx] = var_def else: args[idx] = child.get_resolved_value(blackboard) + elif isinstance(child, FunctionApplicationExpression): + args[idx] = child else: args[idx] = child.get_resolved_value(blackboard) idx += 1 diff --git a/scenario_execution/scenario_execution/osc2_parsing/OpenSCENARIO2Lexer.py b/scenario_execution/scenario_execution/osc2_parsing/OpenSCENARIO2Lexer.py index 1b3b55ee..c529457c 100644 --- a/scenario_execution/scenario_execution/osc2_parsing/OpenSCENARIO2Lexer.py +++ b/scenario_execution/scenario_execution/osc2_parsing/OpenSCENARIO2Lexer.py @@ -1,3 +1,19 @@ +# Copyright (C) 2024 Intel Corporation +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, +# software distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions +# and limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + # Generated from OpenSCENARIO2.g4 by ANTLR 4.9.1 from antlr4 import * from io import StringIO @@ -15,7 +31,6 @@ LanguageParser = getattr(importlib.import_module('{}Parser'.format(module_path)), '{}Parser'.format(language_name)) - def serializedATN(): with StringIO() as buf: buf.write("\3\u608b\ua72a\u8133\ub9ed\u417c\u3be7\u7786\u5964\2l") @@ -425,7 +440,7 @@ class OpenSCENARIO2Lexer(Lexer): atn = ATNDeserializer().deserialize(serializedATN()) - decisionsToDFA = [ DFA(ds, i) for i, ds in enumerate(atn.decisionToState) ] + decisionsToDFA = [DFA(ds, i) for i, ds in enumerate(atn.decisionToState)] T__0 = 1 T__1 = 2 @@ -534,67 +549,65 @@ class OpenSCENARIO2Lexer(Lexer): BoolLiteral = 105 Identifier = 106 - channelNames = [ u"DEFAULT_TOKEN_CHANNEL", u"HIDDEN" ] - - modeNames = [ "DEFAULT_MODE" ] - - literalNames = [ "", - "'import'", "'.'", "'type'", "'is'", "'SI'", "'unit'", "'of'", - "','", "':'", "'factor'", "'offset'", "'kg'", "'m'", "'s'", - "'A'", "'K'", "'mol'", "'cd'", "'rad'", "'enum'", "'='", "'!'", - "'=='", "'struct'", "'inherits'", "'actor'", "'scenario'", "'action'", - "'modifier'", "'extend'", "'global'", "'list'", "'int'", "'uint'", - "'float'", "'bool'", "'string'", "'event'", "'if'", "'@'", "'as'", - "'rise'", "'fall'", "'elapsed'", "'every'", "'var'", "'sample'", - "'with'", "'keep'", "'default'", "'hard'", "'remove_default'", - "'on'", "'do'", "'serial'", "'one_of'", "'parallel'", "'serial_no_memory'", - "'selector'", "'selector_no_memory'", "'wait'", "'emit'", "'call'", - "'until'", "'def'", "'->'", "'expression'", "'undefined'", "'external'", - "'only'", "'cover'", "'record'", "'range'", "'?'", "'=>'", "'or'", - "'and'", "'not'", "'!='", "'<'", "'<='", "'>'", "'>='", "'in'", - "'+'", "'-'", "'*'", "'/'", "'%'", "'it'", "'..'", "'['", "']'", - "'('", "')'" ] - - symbolicNames = [ "", - "NEWLINE", "OPEN_BRACK", "CLOSE_BRACK", "OPEN_PAREN", "CLOSE_PAREN", - "SKIP_", "BLOCK_COMMENT", "LINE_COMMENT", "StringLiteral", "FloatLiteral", - "UintLiteral", "HexUintLiteral", "IntLiteral", "BoolLiteral", - "Identifier" ] - - ruleNames = [ "T__0", "T__1", "T__2", "T__3", "T__4", "T__5", "T__6", - "T__7", "T__8", "T__9", "T__10", "T__11", "T__12", "T__13", - "T__14", "T__15", "T__16", "T__17", "T__18", "T__19", - "T__20", "T__21", "T__22", "T__23", "T__24", "T__25", - "T__26", "T__27", "T__28", "T__29", "T__30", "T__31", - "T__32", "T__33", "T__34", "T__35", "T__36", "T__37", - "T__38", "T__39", "T__40", "T__41", "T__42", "T__43", - "T__44", "T__45", "T__46", "T__47", "T__48", "T__49", - "T__50", "T__51", "T__52", "T__53", "T__54", "T__55", - "T__56", "T__57", "T__58", "T__59", "T__60", "T__61", - "T__62", "T__63", "T__64", "T__65", "T__66", "T__67", - "T__68", "T__69", "T__70", "T__71", "T__72", "T__73", - "T__74", "T__75", "T__76", "T__77", "T__78", "T__79", - "T__80", "T__81", "T__82", "T__83", "T__84", "T__85", - "T__86", "T__87", "T__88", "T__89", "T__90", "NEWLINE", - "OPEN_BRACK", "CLOSE_BRACK", "OPEN_PAREN", "CLOSE_PAREN", - "SKIP_", "SPACES", "LINE_JOINING", "RN", "BLOCK_COMMENT", - "LINE_COMMENT", "StringLiteral", "Shortstring", "ShortstringElem", - "ShortstringChar", "Longstring", "LongstringElem", "LongstringChar", - "StringEscapeSeq", "FloatLiteral", "UintLiteral", "HexUintLiteral", - "IntLiteral", "BoolLiteral", "Identifier", "NonVerticalLineChar", - "Digit", "HexDigit" ] + channelNames = [u"DEFAULT_TOKEN_CHANNEL", u"HIDDEN"] + + modeNames = ["DEFAULT_MODE"] + + literalNames = ["", + "'import'", "'.'", "'type'", "'is'", "'SI'", "'unit'", "'of'", + "','", "':'", "'factor'", "'offset'", "'kg'", "'m'", "'s'", + "'A'", "'K'", "'mol'", "'cd'", "'rad'", "'enum'", "'='", "'!'", + "'=='", "'struct'", "'inherits'", "'actor'", "'scenario'", "'action'", + "'modifier'", "'extend'", "'global'", "'list'", "'int'", "'uint'", + "'float'", "'bool'", "'string'", "'event'", "'if'", "'@'", "'as'", + "'rise'", "'fall'", "'elapsed'", "'every'", "'var'", "'sample'", + "'with'", "'keep'", "'default'", "'hard'", "'remove_default'", + "'on'", "'do'", "'serial'", "'one_of'", "'parallel'", "'serial_no_memory'", + "'selector'", "'selector_no_memory'", "'wait'", "'emit'", "'call'", + "'until'", "'def'", "'->'", "'expression'", "'undefined'", "'external'", + "'only'", "'cover'", "'record'", "'range'", "'?'", "'=>'", "'or'", + "'and'", "'not'", "'!='", "'<'", "'<='", "'>'", "'>='", "'in'", + "'+'", "'-'", "'*'", "'/'", "'%'", "'it'", "'..'", "'['", "']'", + "'('", "')'"] + + symbolicNames = ["", + "NEWLINE", "OPEN_BRACK", "CLOSE_BRACK", "OPEN_PAREN", "CLOSE_PAREN", + "SKIP_", "BLOCK_COMMENT", "LINE_COMMENT", "StringLiteral", "FloatLiteral", + "UintLiteral", "HexUintLiteral", "IntLiteral", "BoolLiteral", + "Identifier"] + + ruleNames = ["T__0", "T__1", "T__2", "T__3", "T__4", "T__5", "T__6", + "T__7", "T__8", "T__9", "T__10", "T__11", "T__12", "T__13", + "T__14", "T__15", "T__16", "T__17", "T__18", "T__19", + "T__20", "T__21", "T__22", "T__23", "T__24", "T__25", + "T__26", "T__27", "T__28", "T__29", "T__30", "T__31", + "T__32", "T__33", "T__34", "T__35", "T__36", "T__37", + "T__38", "T__39", "T__40", "T__41", "T__42", "T__43", + "T__44", "T__45", "T__46", "T__47", "T__48", "T__49", + "T__50", "T__51", "T__52", "T__53", "T__54", "T__55", + "T__56", "T__57", "T__58", "T__59", "T__60", "T__61", + "T__62", "T__63", "T__64", "T__65", "T__66", "T__67", + "T__68", "T__69", "T__70", "T__71", "T__72", "T__73", + "T__74", "T__75", "T__76", "T__77", "T__78", "T__79", + "T__80", "T__81", "T__82", "T__83", "T__84", "T__85", + "T__86", "T__87", "T__88", "T__89", "T__90", "NEWLINE", + "OPEN_BRACK", "CLOSE_BRACK", "OPEN_PAREN", "CLOSE_PAREN", + "SKIP_", "SPACES", "LINE_JOINING", "RN", "BLOCK_COMMENT", + "LINE_COMMENT", "StringLiteral", "Shortstring", "ShortstringElem", + "ShortstringChar", "Longstring", "LongstringElem", "LongstringChar", + "StringEscapeSeq", "FloatLiteral", "UintLiteral", "HexUintLiteral", + "IntLiteral", "BoolLiteral", "Identifier", "NonVerticalLineChar", + "Digit", "HexDigit"] grammarFileName = "OpenSCENARIO2.g4" - def __init__(self, input=None, output:TextIO = sys.stdout): + def __init__(self, input=None, output: TextIO = sys.stdout): super().__init__(input, output) self.checkVersion("4.9.1") self._interp = LexerATNSimulator(self, self.atn, self.decisionsToDFA, PredictionContextCache()) self._actions = None self._predicates = None - - @property def tokens(self): try: @@ -648,7 +661,7 @@ def emitToken(self, t): def nextToken(self): if self._input.LA(1) == Token.EOF and self.indents: - for i in range(len(self.tokens)-1,-1,-1): + for i in range(len(self.tokens)-1, -1, -1): if self.tokens[i].type == Token.EOF: self.tokens.pop(i) self.emitToken(self.commonToken(LanguageParser.NEWLINE, '\n')) @@ -684,16 +697,14 @@ def getIndentationCount(spaces): def atStartOfInput(self): return Lexer.column.fget(self) == 0 and Lexer.line.fget(self) == 1 - - - def action(self, localctx:RuleContext, ruleIndex:int, actionIndex:int): + def action(self, localctx: RuleContext, ruleIndex: int, actionIndex: int): if self._actions is None: actions = dict() - actions[91] = self.NEWLINE_action - actions[92] = self.OPEN_BRACK_action - actions[93] = self.CLOSE_BRACK_action - actions[94] = self.OPEN_PAREN_action - actions[95] = self.CLOSE_PAREN_action + actions[91] = self.NEWLINE_action + actions[92] = self.OPEN_BRACK_action + actions[93] = self.CLOSE_BRACK_action + actions[94] = self.OPEN_PAREN_action + actions[95] = self.CLOSE_PAREN_action self._actions = actions action = self._actions.get(ruleIndex, None) if action is not None: @@ -701,8 +712,7 @@ def action(self, localctx:RuleContext, ruleIndex:int, actionIndex:int): else: raise Exception("No registered action for:" + str(ruleIndex)) - - def NEWLINE_action(self, localctx:RuleContext , actionIndex:int): + def NEWLINE_action(self, localctx: RuleContext, actionIndex: int): if actionIndex == 0: tempt = Lexer.text.fget(self) @@ -738,30 +748,24 @@ def NEWLINE_action(self, localctx:RuleContext , actionIndex:int): while self.indents and self.indents[-1] > indent: self.emitToken(self.createDedent()) self.indents.pop() - - - def OPEN_BRACK_action(self, localctx:RuleContext , actionIndex:int): + def OPEN_BRACK_action(self, localctx: RuleContext, actionIndex: int): if actionIndex == 1: self.opened += 1 - - def CLOSE_BRACK_action(self, localctx:RuleContext , actionIndex:int): + def CLOSE_BRACK_action(self, localctx: RuleContext, actionIndex: int): if actionIndex == 2: self.opened -= 1 - - def OPEN_PAREN_action(self, localctx:RuleContext , actionIndex:int): + def OPEN_PAREN_action(self, localctx: RuleContext, actionIndex: int): if actionIndex == 3: self.opened += 1 - - def CLOSE_PAREN_action(self, localctx:RuleContext , actionIndex:int): + def CLOSE_PAREN_action(self, localctx: RuleContext, actionIndex: int): if actionIndex == 4: self.opened -= 1 - - def sempred(self, localctx:RuleContext, ruleIndex:int, predIndex:int): + def sempred(self, localctx: RuleContext, ruleIndex: int, predIndex: int): if self._predicates is None: preds = dict() preds[91] = self.NEWLINE_sempred @@ -772,9 +776,6 @@ def sempred(self, localctx:RuleContext, ruleIndex:int, predIndex:int): else: raise Exception("No registered predicate for:" + str(ruleIndex)) - def NEWLINE_sempred(self, localctx:RuleContext, predIndex:int): - if predIndex == 0: - return self.atStartOfInput() - - - + def NEWLINE_sempred(self, localctx: RuleContext, predIndex: int): + if predIndex == 0: + return self.atStartOfInput() diff --git a/scenario_execution/scenario_execution/osc2_parsing/OpenSCENARIO2Listener.py b/scenario_execution/scenario_execution/osc2_parsing/OpenSCENARIO2Listener.py index f0c3e568..fe30f814 100644 --- a/scenario_execution/scenario_execution/osc2_parsing/OpenSCENARIO2Listener.py +++ b/scenario_execution/scenario_execution/osc2_parsing/OpenSCENARIO2Listener.py @@ -1,3 +1,19 @@ +# Copyright (C) 2024 Intel Corporation +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, +# software distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions +# and limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + # Generated from OpenSCENARIO2.g4 by ANTLR 4.9.1 from antlr4 import * if __name__ is not None and "." in __name__: @@ -6,1384 +22,1233 @@ from OpenSCENARIO2Parser import OpenSCENARIO2Parser # This class defines a complete listener for a parse tree produced by OpenSCENARIO2Parser. + + class OpenSCENARIO2Listener(ParseTreeListener): # Enter a parse tree produced by OpenSCENARIO2Parser#osc_file. - def enterOsc_file(self, ctx:OpenSCENARIO2Parser.Osc_fileContext): + def enterOsc_file(self, ctx: OpenSCENARIO2Parser.Osc_fileContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#osc_file. - def exitOsc_file(self, ctx:OpenSCENARIO2Parser.Osc_fileContext): + def exitOsc_file(self, ctx: OpenSCENARIO2Parser.Osc_fileContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#preludeStatement. - def enterPreludeStatement(self, ctx:OpenSCENARIO2Parser.PreludeStatementContext): + def enterPreludeStatement(self, ctx: OpenSCENARIO2Parser.PreludeStatementContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#preludeStatement. - def exitPreludeStatement(self, ctx:OpenSCENARIO2Parser.PreludeStatementContext): + def exitPreludeStatement(self, ctx: OpenSCENARIO2Parser.PreludeStatementContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#importStatement. - def enterImportStatement(self, ctx:OpenSCENARIO2Parser.ImportStatementContext): + def enterImportStatement(self, ctx: OpenSCENARIO2Parser.ImportStatementContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#importStatement. - def exitImportStatement(self, ctx:OpenSCENARIO2Parser.ImportStatementContext): + def exitImportStatement(self, ctx: OpenSCENARIO2Parser.ImportStatementContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#importReference. - def enterImportReference(self, ctx:OpenSCENARIO2Parser.ImportReferenceContext): + def enterImportReference(self, ctx: OpenSCENARIO2Parser.ImportReferenceContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#importReference. - def exitImportReference(self, ctx:OpenSCENARIO2Parser.ImportReferenceContext): + def exitImportReference(self, ctx: OpenSCENARIO2Parser.ImportReferenceContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#structuredIdentifier. - def enterStructuredIdentifier(self, ctx:OpenSCENARIO2Parser.StructuredIdentifierContext): + def enterStructuredIdentifier(self, ctx: OpenSCENARIO2Parser.StructuredIdentifierContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#structuredIdentifier. - def exitStructuredIdentifier(self, ctx:OpenSCENARIO2Parser.StructuredIdentifierContext): + def exitStructuredIdentifier(self, ctx: OpenSCENARIO2Parser.StructuredIdentifierContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#oscDeclaration. - def enterOscDeclaration(self, ctx:OpenSCENARIO2Parser.OscDeclarationContext): + def enterOscDeclaration(self, ctx: OpenSCENARIO2Parser.OscDeclarationContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#oscDeclaration. - def exitOscDeclaration(self, ctx:OpenSCENARIO2Parser.OscDeclarationContext): + def exitOscDeclaration(self, ctx: OpenSCENARIO2Parser.OscDeclarationContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#physicalTypeDeclaration. - def enterPhysicalTypeDeclaration(self, ctx:OpenSCENARIO2Parser.PhysicalTypeDeclarationContext): + def enterPhysicalTypeDeclaration(self, ctx: OpenSCENARIO2Parser.PhysicalTypeDeclarationContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#physicalTypeDeclaration. - def exitPhysicalTypeDeclaration(self, ctx:OpenSCENARIO2Parser.PhysicalTypeDeclarationContext): + def exitPhysicalTypeDeclaration(self, ctx: OpenSCENARIO2Parser.PhysicalTypeDeclarationContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#physicalTypeName. - def enterPhysicalTypeName(self, ctx:OpenSCENARIO2Parser.PhysicalTypeNameContext): + def enterPhysicalTypeName(self, ctx: OpenSCENARIO2Parser.PhysicalTypeNameContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#physicalTypeName. - def exitPhysicalTypeName(self, ctx:OpenSCENARIO2Parser.PhysicalTypeNameContext): + def exitPhysicalTypeName(self, ctx: OpenSCENARIO2Parser.PhysicalTypeNameContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#baseUnitSpecifier. - def enterBaseUnitSpecifier(self, ctx:OpenSCENARIO2Parser.BaseUnitSpecifierContext): + def enterBaseUnitSpecifier(self, ctx: OpenSCENARIO2Parser.BaseUnitSpecifierContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#baseUnitSpecifier. - def exitBaseUnitSpecifier(self, ctx:OpenSCENARIO2Parser.BaseUnitSpecifierContext): + def exitBaseUnitSpecifier(self, ctx: OpenSCENARIO2Parser.BaseUnitSpecifierContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#sIBaseUnitSpecifier. - def enterSIBaseUnitSpecifier(self, ctx:OpenSCENARIO2Parser.SIBaseUnitSpecifierContext): + def enterSIBaseUnitSpecifier(self, ctx: OpenSCENARIO2Parser.SIBaseUnitSpecifierContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#sIBaseUnitSpecifier. - def exitSIBaseUnitSpecifier(self, ctx:OpenSCENARIO2Parser.SIBaseUnitSpecifierContext): + def exitSIBaseUnitSpecifier(self, ctx: OpenSCENARIO2Parser.SIBaseUnitSpecifierContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#unitDeclaration. - def enterUnitDeclaration(self, ctx:OpenSCENARIO2Parser.UnitDeclarationContext): + def enterUnitDeclaration(self, ctx: OpenSCENARIO2Parser.UnitDeclarationContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#unitDeclaration. - def exitUnitDeclaration(self, ctx:OpenSCENARIO2Parser.UnitDeclarationContext): + def exitUnitDeclaration(self, ctx: OpenSCENARIO2Parser.UnitDeclarationContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#unitSpecifier. - def enterUnitSpecifier(self, ctx:OpenSCENARIO2Parser.UnitSpecifierContext): + def enterUnitSpecifier(self, ctx: OpenSCENARIO2Parser.UnitSpecifierContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#unitSpecifier. - def exitUnitSpecifier(self, ctx:OpenSCENARIO2Parser.UnitSpecifierContext): + def exitUnitSpecifier(self, ctx: OpenSCENARIO2Parser.UnitSpecifierContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#unitName. - def enterUnitName(self, ctx:OpenSCENARIO2Parser.UnitNameContext): + def enterUnitName(self, ctx: OpenSCENARIO2Parser.UnitNameContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#unitName. - def exitUnitName(self, ctx:OpenSCENARIO2Parser.UnitNameContext): + def exitUnitName(self, ctx: OpenSCENARIO2Parser.UnitNameContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#siBaseExponentList. - def enterSiBaseExponentList(self, ctx:OpenSCENARIO2Parser.SiBaseExponentListContext): + def enterSiBaseExponentList(self, ctx: OpenSCENARIO2Parser.SiBaseExponentListContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#siBaseExponentList. - def exitSiBaseExponentList(self, ctx:OpenSCENARIO2Parser.SiBaseExponentListContext): + def exitSiBaseExponentList(self, ctx: OpenSCENARIO2Parser.SiBaseExponentListContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#siBaseExponent. - def enterSiBaseExponent(self, ctx:OpenSCENARIO2Parser.SiBaseExponentContext): + def enterSiBaseExponent(self, ctx: OpenSCENARIO2Parser.SiBaseExponentContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#siBaseExponent. - def exitSiBaseExponent(self, ctx:OpenSCENARIO2Parser.SiBaseExponentContext): + def exitSiBaseExponent(self, ctx: OpenSCENARIO2Parser.SiBaseExponentContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#siUnitSpecifier. - def enterSiUnitSpecifier(self, ctx:OpenSCENARIO2Parser.SiUnitSpecifierContext): + def enterSiUnitSpecifier(self, ctx: OpenSCENARIO2Parser.SiUnitSpecifierContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#siUnitSpecifier. - def exitSiUnitSpecifier(self, ctx:OpenSCENARIO2Parser.SiUnitSpecifierContext): + def exitSiUnitSpecifier(self, ctx: OpenSCENARIO2Parser.SiUnitSpecifierContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#siFactor. - def enterSiFactor(self, ctx:OpenSCENARIO2Parser.SiFactorContext): + def enterSiFactor(self, ctx: OpenSCENARIO2Parser.SiFactorContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#siFactor. - def exitSiFactor(self, ctx:OpenSCENARIO2Parser.SiFactorContext): + def exitSiFactor(self, ctx: OpenSCENARIO2Parser.SiFactorContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#siOffset. - def enterSiOffset(self, ctx:OpenSCENARIO2Parser.SiOffsetContext): + def enterSiOffset(self, ctx: OpenSCENARIO2Parser.SiOffsetContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#siOffset. - def exitSiOffset(self, ctx:OpenSCENARIO2Parser.SiOffsetContext): + def exitSiOffset(self, ctx: OpenSCENARIO2Parser.SiOffsetContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#siBaseUnitName. - def enterSiBaseUnitName(self, ctx:OpenSCENARIO2Parser.SiBaseUnitNameContext): + def enterSiBaseUnitName(self, ctx: OpenSCENARIO2Parser.SiBaseUnitNameContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#siBaseUnitName. - def exitSiBaseUnitName(self, ctx:OpenSCENARIO2Parser.SiBaseUnitNameContext): + def exitSiBaseUnitName(self, ctx: OpenSCENARIO2Parser.SiBaseUnitNameContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#enumDeclaration. - def enterEnumDeclaration(self, ctx:OpenSCENARIO2Parser.EnumDeclarationContext): + def enterEnumDeclaration(self, ctx: OpenSCENARIO2Parser.EnumDeclarationContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#enumDeclaration. - def exitEnumDeclaration(self, ctx:OpenSCENARIO2Parser.EnumDeclarationContext): + def exitEnumDeclaration(self, ctx: OpenSCENARIO2Parser.EnumDeclarationContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#enumMemberDecl. - def enterEnumMemberDecl(self, ctx:OpenSCENARIO2Parser.EnumMemberDeclContext): + def enterEnumMemberDecl(self, ctx: OpenSCENARIO2Parser.EnumMemberDeclContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#enumMemberDecl. - def exitEnumMemberDecl(self, ctx:OpenSCENARIO2Parser.EnumMemberDeclContext): + def exitEnumMemberDecl(self, ctx: OpenSCENARIO2Parser.EnumMemberDeclContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#enumMemberValue. - def enterEnumMemberValue(self, ctx:OpenSCENARIO2Parser.EnumMemberValueContext): + def enterEnumMemberValue(self, ctx: OpenSCENARIO2Parser.EnumMemberValueContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#enumMemberValue. - def exitEnumMemberValue(self, ctx:OpenSCENARIO2Parser.EnumMemberValueContext): + def exitEnumMemberValue(self, ctx: OpenSCENARIO2Parser.EnumMemberValueContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#enumName. - def enterEnumName(self, ctx:OpenSCENARIO2Parser.EnumNameContext): + def enterEnumName(self, ctx: OpenSCENARIO2Parser.EnumNameContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#enumName. - def exitEnumName(self, ctx:OpenSCENARIO2Parser.EnumNameContext): + def exitEnumName(self, ctx: OpenSCENARIO2Parser.EnumNameContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#enumMemberName. - def enterEnumMemberName(self, ctx:OpenSCENARIO2Parser.EnumMemberNameContext): + def enterEnumMemberName(self, ctx: OpenSCENARIO2Parser.EnumMemberNameContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#enumMemberName. - def exitEnumMemberName(self, ctx:OpenSCENARIO2Parser.EnumMemberNameContext): + def exitEnumMemberName(self, ctx: OpenSCENARIO2Parser.EnumMemberNameContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#enumValueReference. - def enterEnumValueReference(self, ctx:OpenSCENARIO2Parser.EnumValueReferenceContext): + def enterEnumValueReference(self, ctx: OpenSCENARIO2Parser.EnumValueReferenceContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#enumValueReference. - def exitEnumValueReference(self, ctx:OpenSCENARIO2Parser.EnumValueReferenceContext): + def exitEnumValueReference(self, ctx: OpenSCENARIO2Parser.EnumValueReferenceContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#inheritsCondition. - def enterInheritsCondition(self, ctx:OpenSCENARIO2Parser.InheritsConditionContext): + def enterInheritsCondition(self, ctx: OpenSCENARIO2Parser.InheritsConditionContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#inheritsCondition. - def exitInheritsCondition(self, ctx:OpenSCENARIO2Parser.InheritsConditionContext): + def exitInheritsCondition(self, ctx: OpenSCENARIO2Parser.InheritsConditionContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#structDeclaration. - def enterStructDeclaration(self, ctx:OpenSCENARIO2Parser.StructDeclarationContext): + def enterStructDeclaration(self, ctx: OpenSCENARIO2Parser.StructDeclarationContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#structDeclaration. - def exitStructDeclaration(self, ctx:OpenSCENARIO2Parser.StructDeclarationContext): + def exitStructDeclaration(self, ctx: OpenSCENARIO2Parser.StructDeclarationContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#structInherits. - def enterStructInherits(self, ctx:OpenSCENARIO2Parser.StructInheritsContext): + def enterStructInherits(self, ctx: OpenSCENARIO2Parser.StructInheritsContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#structInherits. - def exitStructInherits(self, ctx:OpenSCENARIO2Parser.StructInheritsContext): + def exitStructInherits(self, ctx: OpenSCENARIO2Parser.StructInheritsContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#structMemberDecl. - def enterStructMemberDecl(self, ctx:OpenSCENARIO2Parser.StructMemberDeclContext): + def enterStructMemberDecl(self, ctx: OpenSCENARIO2Parser.StructMemberDeclContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#structMemberDecl. - def exitStructMemberDecl(self, ctx:OpenSCENARIO2Parser.StructMemberDeclContext): + def exitStructMemberDecl(self, ctx: OpenSCENARIO2Parser.StructMemberDeclContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#fieldName. - def enterFieldName(self, ctx:OpenSCENARIO2Parser.FieldNameContext): + def enterFieldName(self, ctx: OpenSCENARIO2Parser.FieldNameContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#fieldName. - def exitFieldName(self, ctx:OpenSCENARIO2Parser.FieldNameContext): + def exitFieldName(self, ctx: OpenSCENARIO2Parser.FieldNameContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#structName. - def enterStructName(self, ctx:OpenSCENARIO2Parser.StructNameContext): + def enterStructName(self, ctx: OpenSCENARIO2Parser.StructNameContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#structName. - def exitStructName(self, ctx:OpenSCENARIO2Parser.StructNameContext): + def exitStructName(self, ctx: OpenSCENARIO2Parser.StructNameContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#actorDeclaration. - def enterActorDeclaration(self, ctx:OpenSCENARIO2Parser.ActorDeclarationContext): + def enterActorDeclaration(self, ctx: OpenSCENARIO2Parser.ActorDeclarationContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#actorDeclaration. - def exitActorDeclaration(self, ctx:OpenSCENARIO2Parser.ActorDeclarationContext): + def exitActorDeclaration(self, ctx: OpenSCENARIO2Parser.ActorDeclarationContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#actorInherits. - def enterActorInherits(self, ctx:OpenSCENARIO2Parser.ActorInheritsContext): + def enterActorInherits(self, ctx: OpenSCENARIO2Parser.ActorInheritsContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#actorInherits. - def exitActorInherits(self, ctx:OpenSCENARIO2Parser.ActorInheritsContext): + def exitActorInherits(self, ctx: OpenSCENARIO2Parser.ActorInheritsContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#actorMemberDecl. - def enterActorMemberDecl(self, ctx:OpenSCENARIO2Parser.ActorMemberDeclContext): + def enterActorMemberDecl(self, ctx: OpenSCENARIO2Parser.ActorMemberDeclContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#actorMemberDecl. - def exitActorMemberDecl(self, ctx:OpenSCENARIO2Parser.ActorMemberDeclContext): + def exitActorMemberDecl(self, ctx: OpenSCENARIO2Parser.ActorMemberDeclContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#actorName. - def enterActorName(self, ctx:OpenSCENARIO2Parser.ActorNameContext): + def enterActorName(self, ctx: OpenSCENARIO2Parser.ActorNameContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#actorName. - def exitActorName(self, ctx:OpenSCENARIO2Parser.ActorNameContext): + def exitActorName(self, ctx: OpenSCENARIO2Parser.ActorNameContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#scenarioDeclaration. - def enterScenarioDeclaration(self, ctx:OpenSCENARIO2Parser.ScenarioDeclarationContext): + def enterScenarioDeclaration(self, ctx: OpenSCENARIO2Parser.ScenarioDeclarationContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#scenarioDeclaration. - def exitScenarioDeclaration(self, ctx:OpenSCENARIO2Parser.ScenarioDeclarationContext): + def exitScenarioDeclaration(self, ctx: OpenSCENARIO2Parser.ScenarioDeclarationContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#scenarioInherits. - def enterScenarioInherits(self, ctx:OpenSCENARIO2Parser.ScenarioInheritsContext): + def enterScenarioInherits(self, ctx: OpenSCENARIO2Parser.ScenarioInheritsContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#scenarioInherits. - def exitScenarioInherits(self, ctx:OpenSCENARIO2Parser.ScenarioInheritsContext): + def exitScenarioInherits(self, ctx: OpenSCENARIO2Parser.ScenarioInheritsContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#scenarioMemberDecl. - def enterScenarioMemberDecl(self, ctx:OpenSCENARIO2Parser.ScenarioMemberDeclContext): + def enterScenarioMemberDecl(self, ctx: OpenSCENARIO2Parser.ScenarioMemberDeclContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#scenarioMemberDecl. - def exitScenarioMemberDecl(self, ctx:OpenSCENARIO2Parser.ScenarioMemberDeclContext): + def exitScenarioMemberDecl(self, ctx: OpenSCENARIO2Parser.ScenarioMemberDeclContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#qualifiedBehaviorName. - def enterQualifiedBehaviorName(self, ctx:OpenSCENARIO2Parser.QualifiedBehaviorNameContext): + def enterQualifiedBehaviorName(self, ctx: OpenSCENARIO2Parser.QualifiedBehaviorNameContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#qualifiedBehaviorName. - def exitQualifiedBehaviorName(self, ctx:OpenSCENARIO2Parser.QualifiedBehaviorNameContext): + def exitQualifiedBehaviorName(self, ctx: OpenSCENARIO2Parser.QualifiedBehaviorNameContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#behaviorName. - def enterBehaviorName(self, ctx:OpenSCENARIO2Parser.BehaviorNameContext): + def enterBehaviorName(self, ctx: OpenSCENARIO2Parser.BehaviorNameContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#behaviorName. - def exitBehaviorName(self, ctx:OpenSCENARIO2Parser.BehaviorNameContext): + def exitBehaviorName(self, ctx: OpenSCENARIO2Parser.BehaviorNameContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#actionDeclaration. - def enterActionDeclaration(self, ctx:OpenSCENARIO2Parser.ActionDeclarationContext): + def enterActionDeclaration(self, ctx: OpenSCENARIO2Parser.ActionDeclarationContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#actionDeclaration. - def exitActionDeclaration(self, ctx:OpenSCENARIO2Parser.ActionDeclarationContext): + def exitActionDeclaration(self, ctx: OpenSCENARIO2Parser.ActionDeclarationContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#actionInherits. - def enterActionInherits(self, ctx:OpenSCENARIO2Parser.ActionInheritsContext): + def enterActionInherits(self, ctx: OpenSCENARIO2Parser.ActionInheritsContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#actionInherits. - def exitActionInherits(self, ctx:OpenSCENARIO2Parser.ActionInheritsContext): + def exitActionInherits(self, ctx: OpenSCENARIO2Parser.ActionInheritsContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#modifierDeclaration. - def enterModifierDeclaration(self, ctx:OpenSCENARIO2Parser.ModifierDeclarationContext): + def enterModifierDeclaration(self, ctx: OpenSCENARIO2Parser.ModifierDeclarationContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#modifierDeclaration. - def exitModifierDeclaration(self, ctx:OpenSCENARIO2Parser.ModifierDeclarationContext): + def exitModifierDeclaration(self, ctx: OpenSCENARIO2Parser.ModifierDeclarationContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#modifierName. - def enterModifierName(self, ctx:OpenSCENARIO2Parser.ModifierNameContext): + def enterModifierName(self, ctx: OpenSCENARIO2Parser.ModifierNameContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#modifierName. - def exitModifierName(self, ctx:OpenSCENARIO2Parser.ModifierNameContext): + def exitModifierName(self, ctx: OpenSCENARIO2Parser.ModifierNameContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#typeExtension. - def enterTypeExtension(self, ctx:OpenSCENARIO2Parser.TypeExtensionContext): + def enterTypeExtension(self, ctx: OpenSCENARIO2Parser.TypeExtensionContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#typeExtension. - def exitTypeExtension(self, ctx:OpenSCENARIO2Parser.TypeExtensionContext): + def exitTypeExtension(self, ctx: OpenSCENARIO2Parser.TypeExtensionContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#enumTypeExtension. - def enterEnumTypeExtension(self, ctx:OpenSCENARIO2Parser.EnumTypeExtensionContext): + def enterEnumTypeExtension(self, ctx: OpenSCENARIO2Parser.EnumTypeExtensionContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#enumTypeExtension. - def exitEnumTypeExtension(self, ctx:OpenSCENARIO2Parser.EnumTypeExtensionContext): + def exitEnumTypeExtension(self, ctx: OpenSCENARIO2Parser.EnumTypeExtensionContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#structuredTypeExtension. - def enterStructuredTypeExtension(self, ctx:OpenSCENARIO2Parser.StructuredTypeExtensionContext): + def enterStructuredTypeExtension(self, ctx: OpenSCENARIO2Parser.StructuredTypeExtensionContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#structuredTypeExtension. - def exitStructuredTypeExtension(self, ctx:OpenSCENARIO2Parser.StructuredTypeExtensionContext): + def exitStructuredTypeExtension(self, ctx: OpenSCENARIO2Parser.StructuredTypeExtensionContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#extendableTypeName. - def enterExtendableTypeName(self, ctx:OpenSCENARIO2Parser.ExtendableTypeNameContext): + def enterExtendableTypeName(self, ctx: OpenSCENARIO2Parser.ExtendableTypeNameContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#extendableTypeName. - def exitExtendableTypeName(self, ctx:OpenSCENARIO2Parser.ExtendableTypeNameContext): + def exitExtendableTypeName(self, ctx: OpenSCENARIO2Parser.ExtendableTypeNameContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#extensionMemberDecl. - def enterExtensionMemberDecl(self, ctx:OpenSCENARIO2Parser.ExtensionMemberDeclContext): + def enterExtensionMemberDecl(self, ctx: OpenSCENARIO2Parser.ExtensionMemberDeclContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#extensionMemberDecl. - def exitExtensionMemberDecl(self, ctx:OpenSCENARIO2Parser.ExtensionMemberDeclContext): + def exitExtensionMemberDecl(self, ctx: OpenSCENARIO2Parser.ExtensionMemberDeclContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#globalParameterDeclaration. - def enterGlobalParameterDeclaration(self, ctx:OpenSCENARIO2Parser.GlobalParameterDeclarationContext): + def enterGlobalParameterDeclaration(self, ctx: OpenSCENARIO2Parser.GlobalParameterDeclarationContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#globalParameterDeclaration. - def exitGlobalParameterDeclaration(self, ctx:OpenSCENARIO2Parser.GlobalParameterDeclarationContext): + def exitGlobalParameterDeclaration(self, ctx: OpenSCENARIO2Parser.GlobalParameterDeclarationContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#typeDeclarator. - def enterTypeDeclarator(self, ctx:OpenSCENARIO2Parser.TypeDeclaratorContext): + def enterTypeDeclarator(self, ctx: OpenSCENARIO2Parser.TypeDeclaratorContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#typeDeclarator. - def exitTypeDeclarator(self, ctx:OpenSCENARIO2Parser.TypeDeclaratorContext): + def exitTypeDeclarator(self, ctx: OpenSCENARIO2Parser.TypeDeclaratorContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#nonAggregateTypeDeclarator. - def enterNonAggregateTypeDeclarator(self, ctx:OpenSCENARIO2Parser.NonAggregateTypeDeclaratorContext): + def enterNonAggregateTypeDeclarator(self, ctx: OpenSCENARIO2Parser.NonAggregateTypeDeclaratorContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#nonAggregateTypeDeclarator. - def exitNonAggregateTypeDeclarator(self, ctx:OpenSCENARIO2Parser.NonAggregateTypeDeclaratorContext): + def exitNonAggregateTypeDeclarator(self, ctx: OpenSCENARIO2Parser.NonAggregateTypeDeclaratorContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#aggregateTypeDeclarator. - def enterAggregateTypeDeclarator(self, ctx:OpenSCENARIO2Parser.AggregateTypeDeclaratorContext): + def enterAggregateTypeDeclarator(self, ctx: OpenSCENARIO2Parser.AggregateTypeDeclaratorContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#aggregateTypeDeclarator. - def exitAggregateTypeDeclarator(self, ctx:OpenSCENARIO2Parser.AggregateTypeDeclaratorContext): + def exitAggregateTypeDeclarator(self, ctx: OpenSCENARIO2Parser.AggregateTypeDeclaratorContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#listTypeDeclarator. - def enterListTypeDeclarator(self, ctx:OpenSCENARIO2Parser.ListTypeDeclaratorContext): + def enterListTypeDeclarator(self, ctx: OpenSCENARIO2Parser.ListTypeDeclaratorContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#listTypeDeclarator. - def exitListTypeDeclarator(self, ctx:OpenSCENARIO2Parser.ListTypeDeclaratorContext): + def exitListTypeDeclarator(self, ctx: OpenSCENARIO2Parser.ListTypeDeclaratorContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#primitiveType. - def enterPrimitiveType(self, ctx:OpenSCENARIO2Parser.PrimitiveTypeContext): + def enterPrimitiveType(self, ctx: OpenSCENARIO2Parser.PrimitiveTypeContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#primitiveType. - def exitPrimitiveType(self, ctx:OpenSCENARIO2Parser.PrimitiveTypeContext): + def exitPrimitiveType(self, ctx: OpenSCENARIO2Parser.PrimitiveTypeContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#typeName. - def enterTypeName(self, ctx:OpenSCENARIO2Parser.TypeNameContext): + def enterTypeName(self, ctx: OpenSCENARIO2Parser.TypeNameContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#typeName. - def exitTypeName(self, ctx:OpenSCENARIO2Parser.TypeNameContext): + def exitTypeName(self, ctx: OpenSCENARIO2Parser.TypeNameContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#eventDeclaration. - def enterEventDeclaration(self, ctx:OpenSCENARIO2Parser.EventDeclarationContext): + def enterEventDeclaration(self, ctx: OpenSCENARIO2Parser.EventDeclarationContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#eventDeclaration. - def exitEventDeclaration(self, ctx:OpenSCENARIO2Parser.EventDeclarationContext): + def exitEventDeclaration(self, ctx: OpenSCENARIO2Parser.EventDeclarationContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#eventSpecification. - def enterEventSpecification(self, ctx:OpenSCENARIO2Parser.EventSpecificationContext): + def enterEventSpecification(self, ctx: OpenSCENARIO2Parser.EventSpecificationContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#eventSpecification. - def exitEventSpecification(self, ctx:OpenSCENARIO2Parser.EventSpecificationContext): + def exitEventSpecification(self, ctx: OpenSCENARIO2Parser.EventSpecificationContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#eventReference. - def enterEventReference(self, ctx:OpenSCENARIO2Parser.EventReferenceContext): + def enterEventReference(self, ctx: OpenSCENARIO2Parser.EventReferenceContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#eventReference. - def exitEventReference(self, ctx:OpenSCENARIO2Parser.EventReferenceContext): + def exitEventReference(self, ctx: OpenSCENARIO2Parser.EventReferenceContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#eventFieldDecl. - def enterEventFieldDecl(self, ctx:OpenSCENARIO2Parser.EventFieldDeclContext): + def enterEventFieldDecl(self, ctx: OpenSCENARIO2Parser.EventFieldDeclContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#eventFieldDecl. - def exitEventFieldDecl(self, ctx:OpenSCENARIO2Parser.EventFieldDeclContext): + def exitEventFieldDecl(self, ctx: OpenSCENARIO2Parser.EventFieldDeclContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#eventFieldName. - def enterEventFieldName(self, ctx:OpenSCENARIO2Parser.EventFieldNameContext): + def enterEventFieldName(self, ctx: OpenSCENARIO2Parser.EventFieldNameContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#eventFieldName. - def exitEventFieldName(self, ctx:OpenSCENARIO2Parser.EventFieldNameContext): + def exitEventFieldName(self, ctx: OpenSCENARIO2Parser.EventFieldNameContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#eventName. - def enterEventName(self, ctx:OpenSCENARIO2Parser.EventNameContext): + def enterEventName(self, ctx: OpenSCENARIO2Parser.EventNameContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#eventName. - def exitEventName(self, ctx:OpenSCENARIO2Parser.EventNameContext): + def exitEventName(self, ctx: OpenSCENARIO2Parser.EventNameContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#eventPath. - def enterEventPath(self, ctx:OpenSCENARIO2Parser.EventPathContext): + def enterEventPath(self, ctx: OpenSCENARIO2Parser.EventPathContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#eventPath. - def exitEventPath(self, ctx:OpenSCENARIO2Parser.EventPathContext): + def exitEventPath(self, ctx: OpenSCENARIO2Parser.EventPathContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#eventCondition. - def enterEventCondition(self, ctx:OpenSCENARIO2Parser.EventConditionContext): + def enterEventCondition(self, ctx: OpenSCENARIO2Parser.EventConditionContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#eventCondition. - def exitEventCondition(self, ctx:OpenSCENARIO2Parser.EventConditionContext): + def exitEventCondition(self, ctx: OpenSCENARIO2Parser.EventConditionContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#riseExpression. - def enterRiseExpression(self, ctx:OpenSCENARIO2Parser.RiseExpressionContext): + def enterRiseExpression(self, ctx: OpenSCENARIO2Parser.RiseExpressionContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#riseExpression. - def exitRiseExpression(self, ctx:OpenSCENARIO2Parser.RiseExpressionContext): + def exitRiseExpression(self, ctx: OpenSCENARIO2Parser.RiseExpressionContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#fallExpression. - def enterFallExpression(self, ctx:OpenSCENARIO2Parser.FallExpressionContext): + def enterFallExpression(self, ctx: OpenSCENARIO2Parser.FallExpressionContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#fallExpression. - def exitFallExpression(self, ctx:OpenSCENARIO2Parser.FallExpressionContext): + def exitFallExpression(self, ctx: OpenSCENARIO2Parser.FallExpressionContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#elapsedExpression. - def enterElapsedExpression(self, ctx:OpenSCENARIO2Parser.ElapsedExpressionContext): + def enterElapsedExpression(self, ctx: OpenSCENARIO2Parser.ElapsedExpressionContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#elapsedExpression. - def exitElapsedExpression(self, ctx:OpenSCENARIO2Parser.ElapsedExpressionContext): + def exitElapsedExpression(self, ctx: OpenSCENARIO2Parser.ElapsedExpressionContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#everyExpression. - def enterEveryExpression(self, ctx:OpenSCENARIO2Parser.EveryExpressionContext): + def enterEveryExpression(self, ctx: OpenSCENARIO2Parser.EveryExpressionContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#everyExpression. - def exitEveryExpression(self, ctx:OpenSCENARIO2Parser.EveryExpressionContext): + def exitEveryExpression(self, ctx: OpenSCENARIO2Parser.EveryExpressionContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#boolExpression. - def enterBoolExpression(self, ctx:OpenSCENARIO2Parser.BoolExpressionContext): + def enterBoolExpression(self, ctx: OpenSCENARIO2Parser.BoolExpressionContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#boolExpression. - def exitBoolExpression(self, ctx:OpenSCENARIO2Parser.BoolExpressionContext): + def exitBoolExpression(self, ctx: OpenSCENARIO2Parser.BoolExpressionContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#durationExpression. - def enterDurationExpression(self, ctx:OpenSCENARIO2Parser.DurationExpressionContext): + def enterDurationExpression(self, ctx: OpenSCENARIO2Parser.DurationExpressionContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#durationExpression. - def exitDurationExpression(self, ctx:OpenSCENARIO2Parser.DurationExpressionContext): + def exitDurationExpression(self, ctx: OpenSCENARIO2Parser.DurationExpressionContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#fieldDeclaration. - def enterFieldDeclaration(self, ctx:OpenSCENARIO2Parser.FieldDeclarationContext): + def enterFieldDeclaration(self, ctx: OpenSCENARIO2Parser.FieldDeclarationContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#fieldDeclaration. - def exitFieldDeclaration(self, ctx:OpenSCENARIO2Parser.FieldDeclarationContext): + def exitFieldDeclaration(self, ctx: OpenSCENARIO2Parser.FieldDeclarationContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#parameterDeclaration. - def enterParameterDeclaration(self, ctx:OpenSCENARIO2Parser.ParameterDeclarationContext): + def enterParameterDeclaration(self, ctx: OpenSCENARIO2Parser.ParameterDeclarationContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#parameterDeclaration. - def exitParameterDeclaration(self, ctx:OpenSCENARIO2Parser.ParameterDeclarationContext): + def exitParameterDeclaration(self, ctx: OpenSCENARIO2Parser.ParameterDeclarationContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#variableDeclaration. - def enterVariableDeclaration(self, ctx:OpenSCENARIO2Parser.VariableDeclarationContext): + def enterVariableDeclaration(self, ctx: OpenSCENARIO2Parser.VariableDeclarationContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#variableDeclaration. - def exitVariableDeclaration(self, ctx:OpenSCENARIO2Parser.VariableDeclarationContext): + def exitVariableDeclaration(self, ctx: OpenSCENARIO2Parser.VariableDeclarationContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#sampleExpression. - def enterSampleExpression(self, ctx:OpenSCENARIO2Parser.SampleExpressionContext): + def enterSampleExpression(self, ctx: OpenSCENARIO2Parser.SampleExpressionContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#sampleExpression. - def exitSampleExpression(self, ctx:OpenSCENARIO2Parser.SampleExpressionContext): + def exitSampleExpression(self, ctx: OpenSCENARIO2Parser.SampleExpressionContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#defaultValue. - def enterDefaultValue(self, ctx:OpenSCENARIO2Parser.DefaultValueContext): + def enterDefaultValue(self, ctx: OpenSCENARIO2Parser.DefaultValueContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#defaultValue. - def exitDefaultValue(self, ctx:OpenSCENARIO2Parser.DefaultValueContext): + def exitDefaultValue(self, ctx: OpenSCENARIO2Parser.DefaultValueContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#parameterWithDeclaration. - def enterParameterWithDeclaration(self, ctx:OpenSCENARIO2Parser.ParameterWithDeclarationContext): + def enterParameterWithDeclaration(self, ctx: OpenSCENARIO2Parser.ParameterWithDeclarationContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#parameterWithDeclaration. - def exitParameterWithDeclaration(self, ctx:OpenSCENARIO2Parser.ParameterWithDeclarationContext): + def exitParameterWithDeclaration(self, ctx: OpenSCENARIO2Parser.ParameterWithDeclarationContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#parameterWithMember. - def enterParameterWithMember(self, ctx:OpenSCENARIO2Parser.ParameterWithMemberContext): + def enterParameterWithMember(self, ctx: OpenSCENARIO2Parser.ParameterWithMemberContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#parameterWithMember. - def exitParameterWithMember(self, ctx:OpenSCENARIO2Parser.ParameterWithMemberContext): + def exitParameterWithMember(self, ctx: OpenSCENARIO2Parser.ParameterWithMemberContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#constraintDeclaration. - def enterConstraintDeclaration(self, ctx:OpenSCENARIO2Parser.ConstraintDeclarationContext): + def enterConstraintDeclaration(self, ctx: OpenSCENARIO2Parser.ConstraintDeclarationContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#constraintDeclaration. - def exitConstraintDeclaration(self, ctx:OpenSCENARIO2Parser.ConstraintDeclarationContext): + def exitConstraintDeclaration(self, ctx: OpenSCENARIO2Parser.ConstraintDeclarationContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#keepConstraintDeclaration. - def enterKeepConstraintDeclaration(self, ctx:OpenSCENARIO2Parser.KeepConstraintDeclarationContext): + def enterKeepConstraintDeclaration(self, ctx: OpenSCENARIO2Parser.KeepConstraintDeclarationContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#keepConstraintDeclaration. - def exitKeepConstraintDeclaration(self, ctx:OpenSCENARIO2Parser.KeepConstraintDeclarationContext): + def exitKeepConstraintDeclaration(self, ctx: OpenSCENARIO2Parser.KeepConstraintDeclarationContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#constraintQualifier. - def enterConstraintQualifier(self, ctx:OpenSCENARIO2Parser.ConstraintQualifierContext): + def enterConstraintQualifier(self, ctx: OpenSCENARIO2Parser.ConstraintQualifierContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#constraintQualifier. - def exitConstraintQualifier(self, ctx:OpenSCENARIO2Parser.ConstraintQualifierContext): + def exitConstraintQualifier(self, ctx: OpenSCENARIO2Parser.ConstraintQualifierContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#constraintExpression. - def enterConstraintExpression(self, ctx:OpenSCENARIO2Parser.ConstraintExpressionContext): + def enterConstraintExpression(self, ctx: OpenSCENARIO2Parser.ConstraintExpressionContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#constraintExpression. - def exitConstraintExpression(self, ctx:OpenSCENARIO2Parser.ConstraintExpressionContext): + def exitConstraintExpression(self, ctx: OpenSCENARIO2Parser.ConstraintExpressionContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#removeDefaultDeclaration. - def enterRemoveDefaultDeclaration(self, ctx:OpenSCENARIO2Parser.RemoveDefaultDeclarationContext): + def enterRemoveDefaultDeclaration(self, ctx: OpenSCENARIO2Parser.RemoveDefaultDeclarationContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#removeDefaultDeclaration. - def exitRemoveDefaultDeclaration(self, ctx:OpenSCENARIO2Parser.RemoveDefaultDeclarationContext): + def exitRemoveDefaultDeclaration(self, ctx: OpenSCENARIO2Parser.RemoveDefaultDeclarationContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#parameterReference. - def enterParameterReference(self, ctx:OpenSCENARIO2Parser.ParameterReferenceContext): + def enterParameterReference(self, ctx: OpenSCENARIO2Parser.ParameterReferenceContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#parameterReference. - def exitParameterReference(self, ctx:OpenSCENARIO2Parser.ParameterReferenceContext): + def exitParameterReference(self, ctx: OpenSCENARIO2Parser.ParameterReferenceContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#modifierInvocation. - def enterModifierInvocation(self, ctx:OpenSCENARIO2Parser.ModifierInvocationContext): + def enterModifierInvocation(self, ctx: OpenSCENARIO2Parser.ModifierInvocationContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#modifierInvocation. - def exitModifierInvocation(self, ctx:OpenSCENARIO2Parser.ModifierInvocationContext): + def exitModifierInvocation(self, ctx: OpenSCENARIO2Parser.ModifierInvocationContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#behaviorExpression. - def enterBehaviorExpression(self, ctx:OpenSCENARIO2Parser.BehaviorExpressionContext): + def enterBehaviorExpression(self, ctx: OpenSCENARIO2Parser.BehaviorExpressionContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#behaviorExpression. - def exitBehaviorExpression(self, ctx:OpenSCENARIO2Parser.BehaviorExpressionContext): + def exitBehaviorExpression(self, ctx: OpenSCENARIO2Parser.BehaviorExpressionContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#behaviorSpecification. - def enterBehaviorSpecification(self, ctx:OpenSCENARIO2Parser.BehaviorSpecificationContext): + def enterBehaviorSpecification(self, ctx: OpenSCENARIO2Parser.BehaviorSpecificationContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#behaviorSpecification. - def exitBehaviorSpecification(self, ctx:OpenSCENARIO2Parser.BehaviorSpecificationContext): + def exitBehaviorSpecification(self, ctx: OpenSCENARIO2Parser.BehaviorSpecificationContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#onDirective. - def enterOnDirective(self, ctx:OpenSCENARIO2Parser.OnDirectiveContext): + def enterOnDirective(self, ctx: OpenSCENARIO2Parser.OnDirectiveContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#onDirective. - def exitOnDirective(self, ctx:OpenSCENARIO2Parser.OnDirectiveContext): + def exitOnDirective(self, ctx: OpenSCENARIO2Parser.OnDirectiveContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#onMember. - def enterOnMember(self, ctx:OpenSCENARIO2Parser.OnMemberContext): + def enterOnMember(self, ctx: OpenSCENARIO2Parser.OnMemberContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#onMember. - def exitOnMember(self, ctx:OpenSCENARIO2Parser.OnMemberContext): + def exitOnMember(self, ctx: OpenSCENARIO2Parser.OnMemberContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#doDirective. - def enterDoDirective(self, ctx:OpenSCENARIO2Parser.DoDirectiveContext): + def enterDoDirective(self, ctx: OpenSCENARIO2Parser.DoDirectiveContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#doDirective. - def exitDoDirective(self, ctx:OpenSCENARIO2Parser.DoDirectiveContext): + def exitDoDirective(self, ctx: OpenSCENARIO2Parser.DoDirectiveContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#doMember. - def enterDoMember(self, ctx:OpenSCENARIO2Parser.DoMemberContext): + def enterDoMember(self, ctx: OpenSCENARIO2Parser.DoMemberContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#doMember. - def exitDoMember(self, ctx:OpenSCENARIO2Parser.DoMemberContext): + def exitDoMember(self, ctx: OpenSCENARIO2Parser.DoMemberContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#composition. - def enterComposition(self, ctx:OpenSCENARIO2Parser.CompositionContext): + def enterComposition(self, ctx: OpenSCENARIO2Parser.CompositionContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#composition. - def exitComposition(self, ctx:OpenSCENARIO2Parser.CompositionContext): + def exitComposition(self, ctx: OpenSCENARIO2Parser.CompositionContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#compositionOperator. - def enterCompositionOperator(self, ctx:OpenSCENARIO2Parser.CompositionOperatorContext): + def enterCompositionOperator(self, ctx: OpenSCENARIO2Parser.CompositionOperatorContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#compositionOperator. - def exitCompositionOperator(self, ctx:OpenSCENARIO2Parser.CompositionOperatorContext): + def exitCompositionOperator(self, ctx: OpenSCENARIO2Parser.CompositionOperatorContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#behaviorInvocation. - def enterBehaviorInvocation(self, ctx:OpenSCENARIO2Parser.BehaviorInvocationContext): + def enterBehaviorInvocation(self, ctx: OpenSCENARIO2Parser.BehaviorInvocationContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#behaviorInvocation. - def exitBehaviorInvocation(self, ctx:OpenSCENARIO2Parser.BehaviorInvocationContext): + def exitBehaviorInvocation(self, ctx: OpenSCENARIO2Parser.BehaviorInvocationContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#behaviorWithDeclaration. - def enterBehaviorWithDeclaration(self, ctx:OpenSCENARIO2Parser.BehaviorWithDeclarationContext): + def enterBehaviorWithDeclaration(self, ctx: OpenSCENARIO2Parser.BehaviorWithDeclarationContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#behaviorWithDeclaration. - def exitBehaviorWithDeclaration(self, ctx:OpenSCENARIO2Parser.BehaviorWithDeclarationContext): + def exitBehaviorWithDeclaration(self, ctx: OpenSCENARIO2Parser.BehaviorWithDeclarationContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#behaviorWithMember. - def enterBehaviorWithMember(self, ctx:OpenSCENARIO2Parser.BehaviorWithMemberContext): + def enterBehaviorWithMember(self, ctx: OpenSCENARIO2Parser.BehaviorWithMemberContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#behaviorWithMember. - def exitBehaviorWithMember(self, ctx:OpenSCENARIO2Parser.BehaviorWithMemberContext): + def exitBehaviorWithMember(self, ctx: OpenSCENARIO2Parser.BehaviorWithMemberContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#labelName. - def enterLabelName(self, ctx:OpenSCENARIO2Parser.LabelNameContext): + def enterLabelName(self, ctx: OpenSCENARIO2Parser.LabelNameContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#labelName. - def exitLabelName(self, ctx:OpenSCENARIO2Parser.LabelNameContext): + def exitLabelName(self, ctx: OpenSCENARIO2Parser.LabelNameContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#actorExpression. - def enterActorExpression(self, ctx:OpenSCENARIO2Parser.ActorExpressionContext): + def enterActorExpression(self, ctx: OpenSCENARIO2Parser.ActorExpressionContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#actorExpression. - def exitActorExpression(self, ctx:OpenSCENARIO2Parser.ActorExpressionContext): + def exitActorExpression(self, ctx: OpenSCENARIO2Parser.ActorExpressionContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#waitDirective. - def enterWaitDirective(self, ctx:OpenSCENARIO2Parser.WaitDirectiveContext): + def enterWaitDirective(self, ctx: OpenSCENARIO2Parser.WaitDirectiveContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#waitDirective. - def exitWaitDirective(self, ctx:OpenSCENARIO2Parser.WaitDirectiveContext): + def exitWaitDirective(self, ctx: OpenSCENARIO2Parser.WaitDirectiveContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#emitDirective. - def enterEmitDirective(self, ctx:OpenSCENARIO2Parser.EmitDirectiveContext): + def enterEmitDirective(self, ctx: OpenSCENARIO2Parser.EmitDirectiveContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#emitDirective. - def exitEmitDirective(self, ctx:OpenSCENARIO2Parser.EmitDirectiveContext): + def exitEmitDirective(self, ctx: OpenSCENARIO2Parser.EmitDirectiveContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#callDirective. - def enterCallDirective(self, ctx:OpenSCENARIO2Parser.CallDirectiveContext): + def enterCallDirective(self, ctx: OpenSCENARIO2Parser.CallDirectiveContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#callDirective. - def exitCallDirective(self, ctx:OpenSCENARIO2Parser.CallDirectiveContext): + def exitCallDirective(self, ctx: OpenSCENARIO2Parser.CallDirectiveContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#untilDirective. - def enterUntilDirective(self, ctx:OpenSCENARIO2Parser.UntilDirectiveContext): + def enterUntilDirective(self, ctx: OpenSCENARIO2Parser.UntilDirectiveContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#untilDirective. - def exitUntilDirective(self, ctx:OpenSCENARIO2Parser.UntilDirectiveContext): + def exitUntilDirective(self, ctx: OpenSCENARIO2Parser.UntilDirectiveContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#methodInvocation. - def enterMethodInvocation(self, ctx:OpenSCENARIO2Parser.MethodInvocationContext): + def enterMethodInvocation(self, ctx: OpenSCENARIO2Parser.MethodInvocationContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#methodInvocation. - def exitMethodInvocation(self, ctx:OpenSCENARIO2Parser.MethodInvocationContext): + def exitMethodInvocation(self, ctx: OpenSCENARIO2Parser.MethodInvocationContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#methodDeclaration. - def enterMethodDeclaration(self, ctx:OpenSCENARIO2Parser.MethodDeclarationContext): + def enterMethodDeclaration(self, ctx: OpenSCENARIO2Parser.MethodDeclarationContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#methodDeclaration. - def exitMethodDeclaration(self, ctx:OpenSCENARIO2Parser.MethodDeclarationContext): + def exitMethodDeclaration(self, ctx: OpenSCENARIO2Parser.MethodDeclarationContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#returnType. - def enterReturnType(self, ctx:OpenSCENARIO2Parser.ReturnTypeContext): + def enterReturnType(self, ctx: OpenSCENARIO2Parser.ReturnTypeContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#returnType. - def exitReturnType(self, ctx:OpenSCENARIO2Parser.ReturnTypeContext): + def exitReturnType(self, ctx: OpenSCENARIO2Parser.ReturnTypeContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#methodImplementation. - def enterMethodImplementation(self, ctx:OpenSCENARIO2Parser.MethodImplementationContext): + def enterMethodImplementation(self, ctx: OpenSCENARIO2Parser.MethodImplementationContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#methodImplementation. - def exitMethodImplementation(self, ctx:OpenSCENARIO2Parser.MethodImplementationContext): + def exitMethodImplementation(self, ctx: OpenSCENARIO2Parser.MethodImplementationContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#methodQualifier. - def enterMethodQualifier(self, ctx:OpenSCENARIO2Parser.MethodQualifierContext): + def enterMethodQualifier(self, ctx: OpenSCENARIO2Parser.MethodQualifierContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#methodQualifier. - def exitMethodQualifier(self, ctx:OpenSCENARIO2Parser.MethodQualifierContext): + def exitMethodQualifier(self, ctx: OpenSCENARIO2Parser.MethodQualifierContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#methodName. - def enterMethodName(self, ctx:OpenSCENARIO2Parser.MethodNameContext): + def enterMethodName(self, ctx: OpenSCENARIO2Parser.MethodNameContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#methodName. - def exitMethodName(self, ctx:OpenSCENARIO2Parser.MethodNameContext): + def exitMethodName(self, ctx: OpenSCENARIO2Parser.MethodNameContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#coverageDeclaration. - def enterCoverageDeclaration(self, ctx:OpenSCENARIO2Parser.CoverageDeclarationContext): + def enterCoverageDeclaration(self, ctx: OpenSCENARIO2Parser.CoverageDeclarationContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#coverageDeclaration. - def exitCoverageDeclaration(self, ctx:OpenSCENARIO2Parser.CoverageDeclarationContext): + def exitCoverageDeclaration(self, ctx: OpenSCENARIO2Parser.CoverageDeclarationContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#coverDeclaration. - def enterCoverDeclaration(self, ctx:OpenSCENARIO2Parser.CoverDeclarationContext): + def enterCoverDeclaration(self, ctx: OpenSCENARIO2Parser.CoverDeclarationContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#coverDeclaration. - def exitCoverDeclaration(self, ctx:OpenSCENARIO2Parser.CoverDeclarationContext): + def exitCoverDeclaration(self, ctx: OpenSCENARIO2Parser.CoverDeclarationContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#recordDeclaration. - def enterRecordDeclaration(self, ctx:OpenSCENARIO2Parser.RecordDeclarationContext): + def enterRecordDeclaration(self, ctx: OpenSCENARIO2Parser.RecordDeclarationContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#recordDeclaration. - def exitRecordDeclaration(self, ctx:OpenSCENARIO2Parser.RecordDeclarationContext): + def exitRecordDeclaration(self, ctx: OpenSCENARIO2Parser.RecordDeclarationContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#coverageExpression. - def enterCoverageExpression(self, ctx:OpenSCENARIO2Parser.CoverageExpressionContext): + def enterCoverageExpression(self, ctx: OpenSCENARIO2Parser.CoverageExpressionContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#coverageExpression. - def exitCoverageExpression(self, ctx:OpenSCENARIO2Parser.CoverageExpressionContext): + def exitCoverageExpression(self, ctx: OpenSCENARIO2Parser.CoverageExpressionContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#coverageUnit. - def enterCoverageUnit(self, ctx:OpenSCENARIO2Parser.CoverageUnitContext): + def enterCoverageUnit(self, ctx: OpenSCENARIO2Parser.CoverageUnitContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#coverageUnit. - def exitCoverageUnit(self, ctx:OpenSCENARIO2Parser.CoverageUnitContext): + def exitCoverageUnit(self, ctx: OpenSCENARIO2Parser.CoverageUnitContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#coverageRange. - def enterCoverageRange(self, ctx:OpenSCENARIO2Parser.CoverageRangeContext): + def enterCoverageRange(self, ctx: OpenSCENARIO2Parser.CoverageRangeContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#coverageRange. - def exitCoverageRange(self, ctx:OpenSCENARIO2Parser.CoverageRangeContext): + def exitCoverageRange(self, ctx: OpenSCENARIO2Parser.CoverageRangeContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#coverageEvery. - def enterCoverageEvery(self, ctx:OpenSCENARIO2Parser.CoverageEveryContext): + def enterCoverageEvery(self, ctx: OpenSCENARIO2Parser.CoverageEveryContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#coverageEvery. - def exitCoverageEvery(self, ctx:OpenSCENARIO2Parser.CoverageEveryContext): + def exitCoverageEvery(self, ctx: OpenSCENARIO2Parser.CoverageEveryContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#coverageEvent. - def enterCoverageEvent(self, ctx:OpenSCENARIO2Parser.CoverageEventContext): + def enterCoverageEvent(self, ctx: OpenSCENARIO2Parser.CoverageEventContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#coverageEvent. - def exitCoverageEvent(self, ctx:OpenSCENARIO2Parser.CoverageEventContext): + def exitCoverageEvent(self, ctx: OpenSCENARIO2Parser.CoverageEventContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#coverageNameArgument. - def enterCoverageNameArgument(self, ctx:OpenSCENARIO2Parser.CoverageNameArgumentContext): + def enterCoverageNameArgument(self, ctx: OpenSCENARIO2Parser.CoverageNameArgumentContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#coverageNameArgument. - def exitCoverageNameArgument(self, ctx:OpenSCENARIO2Parser.CoverageNameArgumentContext): + def exitCoverageNameArgument(self, ctx: OpenSCENARIO2Parser.CoverageNameArgumentContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#targetName. - def enterTargetName(self, ctx:OpenSCENARIO2Parser.TargetNameContext): + def enterTargetName(self, ctx: OpenSCENARIO2Parser.TargetNameContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#targetName. - def exitTargetName(self, ctx:OpenSCENARIO2Parser.TargetNameContext): + def exitTargetName(self, ctx: OpenSCENARIO2Parser.TargetNameContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#expression. - def enterExpression(self, ctx:OpenSCENARIO2Parser.ExpressionContext): + def enterExpression(self, ctx: OpenSCENARIO2Parser.ExpressionContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#expression. - def exitExpression(self, ctx:OpenSCENARIO2Parser.ExpressionContext): + def exitExpression(self, ctx: OpenSCENARIO2Parser.ExpressionContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#ternaryOpExp. - def enterTernaryOpExp(self, ctx:OpenSCENARIO2Parser.TernaryOpExpContext): + def enterTernaryOpExp(self, ctx: OpenSCENARIO2Parser.TernaryOpExpContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#ternaryOpExp. - def exitTernaryOpExp(self, ctx:OpenSCENARIO2Parser.TernaryOpExpContext): + def exitTernaryOpExp(self, ctx: OpenSCENARIO2Parser.TernaryOpExpContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#implication. - def enterImplication(self, ctx:OpenSCENARIO2Parser.ImplicationContext): + def enterImplication(self, ctx: OpenSCENARIO2Parser.ImplicationContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#implication. - def exitImplication(self, ctx:OpenSCENARIO2Parser.ImplicationContext): + def exitImplication(self, ctx: OpenSCENARIO2Parser.ImplicationContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#disjunction. - def enterDisjunction(self, ctx:OpenSCENARIO2Parser.DisjunctionContext): + def enterDisjunction(self, ctx: OpenSCENARIO2Parser.DisjunctionContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#disjunction. - def exitDisjunction(self, ctx:OpenSCENARIO2Parser.DisjunctionContext): + def exitDisjunction(self, ctx: OpenSCENARIO2Parser.DisjunctionContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#conjunction. - def enterConjunction(self, ctx:OpenSCENARIO2Parser.ConjunctionContext): + def enterConjunction(self, ctx: OpenSCENARIO2Parser.ConjunctionContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#conjunction. - def exitConjunction(self, ctx:OpenSCENARIO2Parser.ConjunctionContext): + def exitConjunction(self, ctx: OpenSCENARIO2Parser.ConjunctionContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#inversion. - def enterInversion(self, ctx:OpenSCENARIO2Parser.InversionContext): + def enterInversion(self, ctx: OpenSCENARIO2Parser.InversionContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#inversion. - def exitInversion(self, ctx:OpenSCENARIO2Parser.InversionContext): + def exitInversion(self, ctx: OpenSCENARIO2Parser.InversionContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#relationExp. - def enterRelationExp(self, ctx:OpenSCENARIO2Parser.RelationExpContext): + def enterRelationExp(self, ctx: OpenSCENARIO2Parser.RelationExpContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#relationExp. - def exitRelationExp(self, ctx:OpenSCENARIO2Parser.RelationExpContext): + def exitRelationExp(self, ctx: OpenSCENARIO2Parser.RelationExpContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#sumExp. - def enterSumExp(self, ctx:OpenSCENARIO2Parser.SumExpContext): + def enterSumExp(self, ctx: OpenSCENARIO2Parser.SumExpContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#sumExp. - def exitSumExp(self, ctx:OpenSCENARIO2Parser.SumExpContext): + def exitSumExp(self, ctx: OpenSCENARIO2Parser.SumExpContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#relationalOp. - def enterRelationalOp(self, ctx:OpenSCENARIO2Parser.RelationalOpContext): + def enterRelationalOp(self, ctx: OpenSCENARIO2Parser.RelationalOpContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#relationalOp. - def exitRelationalOp(self, ctx:OpenSCENARIO2Parser.RelationalOpContext): + def exitRelationalOp(self, ctx: OpenSCENARIO2Parser.RelationalOpContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#termExp. - def enterTermExp(self, ctx:OpenSCENARIO2Parser.TermExpContext): + def enterTermExp(self, ctx: OpenSCENARIO2Parser.TermExpContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#termExp. - def exitTermExp(self, ctx:OpenSCENARIO2Parser.TermExpContext): + def exitTermExp(self, ctx: OpenSCENARIO2Parser.TermExpContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#additiveExp. - def enterAdditiveExp(self, ctx:OpenSCENARIO2Parser.AdditiveExpContext): + def enterAdditiveExp(self, ctx: OpenSCENARIO2Parser.AdditiveExpContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#additiveExp. - def exitAdditiveExp(self, ctx:OpenSCENARIO2Parser.AdditiveExpContext): + def exitAdditiveExp(self, ctx: OpenSCENARIO2Parser.AdditiveExpContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#additiveOp. - def enterAdditiveOp(self, ctx:OpenSCENARIO2Parser.AdditiveOpContext): + def enterAdditiveOp(self, ctx: OpenSCENARIO2Parser.AdditiveOpContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#additiveOp. - def exitAdditiveOp(self, ctx:OpenSCENARIO2Parser.AdditiveOpContext): + def exitAdditiveOp(self, ctx: OpenSCENARIO2Parser.AdditiveOpContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#multiplicativeExp. - def enterMultiplicativeExp(self, ctx:OpenSCENARIO2Parser.MultiplicativeExpContext): + def enterMultiplicativeExp(self, ctx: OpenSCENARIO2Parser.MultiplicativeExpContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#multiplicativeExp. - def exitMultiplicativeExp(self, ctx:OpenSCENARIO2Parser.MultiplicativeExpContext): + def exitMultiplicativeExp(self, ctx: OpenSCENARIO2Parser.MultiplicativeExpContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#factorExp. - def enterFactorExp(self, ctx:OpenSCENARIO2Parser.FactorExpContext): + def enterFactorExp(self, ctx: OpenSCENARIO2Parser.FactorExpContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#factorExp. - def exitFactorExp(self, ctx:OpenSCENARIO2Parser.FactorExpContext): + def exitFactorExp(self, ctx: OpenSCENARIO2Parser.FactorExpContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#multiplicativeOp. - def enterMultiplicativeOp(self, ctx:OpenSCENARIO2Parser.MultiplicativeOpContext): + def enterMultiplicativeOp(self, ctx: OpenSCENARIO2Parser.MultiplicativeOpContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#multiplicativeOp. - def exitMultiplicativeOp(self, ctx:OpenSCENARIO2Parser.MultiplicativeOpContext): + def exitMultiplicativeOp(self, ctx: OpenSCENARIO2Parser.MultiplicativeOpContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#factor. - def enterFactor(self, ctx:OpenSCENARIO2Parser.FactorContext): + def enterFactor(self, ctx: OpenSCENARIO2Parser.FactorContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#factor. - def exitFactor(self, ctx:OpenSCENARIO2Parser.FactorContext): + def exitFactor(self, ctx: OpenSCENARIO2Parser.FactorContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#primaryExpression. - def enterPrimaryExpression(self, ctx:OpenSCENARIO2Parser.PrimaryExpressionContext): + def enterPrimaryExpression(self, ctx: OpenSCENARIO2Parser.PrimaryExpressionContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#primaryExpression. - def exitPrimaryExpression(self, ctx:OpenSCENARIO2Parser.PrimaryExpressionContext): + def exitPrimaryExpression(self, ctx: OpenSCENARIO2Parser.PrimaryExpressionContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#castExpression. - def enterCastExpression(self, ctx:OpenSCENARIO2Parser.CastExpressionContext): + def enterCastExpression(self, ctx: OpenSCENARIO2Parser.CastExpressionContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#castExpression. - def exitCastExpression(self, ctx:OpenSCENARIO2Parser.CastExpressionContext): + def exitCastExpression(self, ctx: OpenSCENARIO2Parser.CastExpressionContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#functionApplicationExpression. - def enterFunctionApplicationExpression(self, ctx:OpenSCENARIO2Parser.FunctionApplicationExpressionContext): + def enterFunctionApplicationExpression(self, ctx: OpenSCENARIO2Parser.FunctionApplicationExpressionContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#functionApplicationExpression. - def exitFunctionApplicationExpression(self, ctx:OpenSCENARIO2Parser.FunctionApplicationExpressionContext): + def exitFunctionApplicationExpression(self, ctx: OpenSCENARIO2Parser.FunctionApplicationExpressionContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#fieldAccessExpression. - def enterFieldAccessExpression(self, ctx:OpenSCENARIO2Parser.FieldAccessExpressionContext): + def enterFieldAccessExpression(self, ctx: OpenSCENARIO2Parser.FieldAccessExpressionContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#fieldAccessExpression. - def exitFieldAccessExpression(self, ctx:OpenSCENARIO2Parser.FieldAccessExpressionContext): + def exitFieldAccessExpression(self, ctx: OpenSCENARIO2Parser.FieldAccessExpressionContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#elementAccessExpression. - def enterElementAccessExpression(self, ctx:OpenSCENARIO2Parser.ElementAccessExpressionContext): + def enterElementAccessExpression(self, ctx: OpenSCENARIO2Parser.ElementAccessExpressionContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#elementAccessExpression. - def exitElementAccessExpression(self, ctx:OpenSCENARIO2Parser.ElementAccessExpressionContext): + def exitElementAccessExpression(self, ctx: OpenSCENARIO2Parser.ElementAccessExpressionContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#typeTestExpression. - def enterTypeTestExpression(self, ctx:OpenSCENARIO2Parser.TypeTestExpressionContext): + def enterTypeTestExpression(self, ctx: OpenSCENARIO2Parser.TypeTestExpressionContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#typeTestExpression. - def exitTypeTestExpression(self, ctx:OpenSCENARIO2Parser.TypeTestExpressionContext): + def exitTypeTestExpression(self, ctx: OpenSCENARIO2Parser.TypeTestExpressionContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#fieldAccess. - def enterFieldAccess(self, ctx:OpenSCENARIO2Parser.FieldAccessContext): + def enterFieldAccess(self, ctx: OpenSCENARIO2Parser.FieldAccessContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#fieldAccess. - def exitFieldAccess(self, ctx:OpenSCENARIO2Parser.FieldAccessContext): + def exitFieldAccess(self, ctx: OpenSCENARIO2Parser.FieldAccessContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#primaryExp. - def enterPrimaryExp(self, ctx:OpenSCENARIO2Parser.PrimaryExpContext): + def enterPrimaryExp(self, ctx: OpenSCENARIO2Parser.PrimaryExpContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#primaryExp. - def exitPrimaryExp(self, ctx:OpenSCENARIO2Parser.PrimaryExpContext): + def exitPrimaryExp(self, ctx: OpenSCENARIO2Parser.PrimaryExpContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#valueExp. - def enterValueExp(self, ctx:OpenSCENARIO2Parser.ValueExpContext): + def enterValueExp(self, ctx: OpenSCENARIO2Parser.ValueExpContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#valueExp. - def exitValueExp(self, ctx:OpenSCENARIO2Parser.ValueExpContext): + def exitValueExp(self, ctx: OpenSCENARIO2Parser.ValueExpContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#listConstructor. - def enterListConstructor(self, ctx:OpenSCENARIO2Parser.ListConstructorContext): + def enterListConstructor(self, ctx: OpenSCENARIO2Parser.ListConstructorContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#listConstructor. - def exitListConstructor(self, ctx:OpenSCENARIO2Parser.ListConstructorContext): + def exitListConstructor(self, ctx: OpenSCENARIO2Parser.ListConstructorContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#rangeConstructor. - def enterRangeConstructor(self, ctx:OpenSCENARIO2Parser.RangeConstructorContext): + def enterRangeConstructor(self, ctx: OpenSCENARIO2Parser.RangeConstructorContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#rangeConstructor. - def exitRangeConstructor(self, ctx:OpenSCENARIO2Parser.RangeConstructorContext): + def exitRangeConstructor(self, ctx: OpenSCENARIO2Parser.RangeConstructorContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#identifierReference. - def enterIdentifierReference(self, ctx:OpenSCENARIO2Parser.IdentifierReferenceContext): + def enterIdentifierReference(self, ctx: OpenSCENARIO2Parser.IdentifierReferenceContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#identifierReference. - def exitIdentifierReference(self, ctx:OpenSCENARIO2Parser.IdentifierReferenceContext): + def exitIdentifierReference(self, ctx: OpenSCENARIO2Parser.IdentifierReferenceContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#argumentListSpecification. - def enterArgumentListSpecification(self, ctx:OpenSCENARIO2Parser.ArgumentListSpecificationContext): + def enterArgumentListSpecification(self, ctx: OpenSCENARIO2Parser.ArgumentListSpecificationContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#argumentListSpecification. - def exitArgumentListSpecification(self, ctx:OpenSCENARIO2Parser.ArgumentListSpecificationContext): + def exitArgumentListSpecification(self, ctx: OpenSCENARIO2Parser.ArgumentListSpecificationContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#argumentSpecification. - def enterArgumentSpecification(self, ctx:OpenSCENARIO2Parser.ArgumentSpecificationContext): + def enterArgumentSpecification(self, ctx: OpenSCENARIO2Parser.ArgumentSpecificationContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#argumentSpecification. - def exitArgumentSpecification(self, ctx:OpenSCENARIO2Parser.ArgumentSpecificationContext): + def exitArgumentSpecification(self, ctx: OpenSCENARIO2Parser.ArgumentSpecificationContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#argumentName. - def enterArgumentName(self, ctx:OpenSCENARIO2Parser.ArgumentNameContext): + def enterArgumentName(self, ctx: OpenSCENARIO2Parser.ArgumentNameContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#argumentName. - def exitArgumentName(self, ctx:OpenSCENARIO2Parser.ArgumentNameContext): + def exitArgumentName(self, ctx: OpenSCENARIO2Parser.ArgumentNameContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#argumentList. - def enterArgumentList(self, ctx:OpenSCENARIO2Parser.ArgumentListContext): + def enterArgumentList(self, ctx: OpenSCENARIO2Parser.ArgumentListContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#argumentList. - def exitArgumentList(self, ctx:OpenSCENARIO2Parser.ArgumentListContext): + def exitArgumentList(self, ctx: OpenSCENARIO2Parser.ArgumentListContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#positionalArgument. - def enterPositionalArgument(self, ctx:OpenSCENARIO2Parser.PositionalArgumentContext): + def enterPositionalArgument(self, ctx: OpenSCENARIO2Parser.PositionalArgumentContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#positionalArgument. - def exitPositionalArgument(self, ctx:OpenSCENARIO2Parser.PositionalArgumentContext): + def exitPositionalArgument(self, ctx: OpenSCENARIO2Parser.PositionalArgumentContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#namedArgument. - def enterNamedArgument(self, ctx:OpenSCENARIO2Parser.NamedArgumentContext): + def enterNamedArgument(self, ctx: OpenSCENARIO2Parser.NamedArgumentContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#namedArgument. - def exitNamedArgument(self, ctx:OpenSCENARIO2Parser.NamedArgumentContext): + def exitNamedArgument(self, ctx: OpenSCENARIO2Parser.NamedArgumentContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#physicalLiteral. - def enterPhysicalLiteral(self, ctx:OpenSCENARIO2Parser.PhysicalLiteralContext): + def enterPhysicalLiteral(self, ctx: OpenSCENARIO2Parser.PhysicalLiteralContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#physicalLiteral. - def exitPhysicalLiteral(self, ctx:OpenSCENARIO2Parser.PhysicalLiteralContext): + def exitPhysicalLiteral(self, ctx: OpenSCENARIO2Parser.PhysicalLiteralContext): pass - # Enter a parse tree produced by OpenSCENARIO2Parser#integerLiteral. - def enterIntegerLiteral(self, ctx:OpenSCENARIO2Parser.IntegerLiteralContext): + def enterIntegerLiteral(self, ctx: OpenSCENARIO2Parser.IntegerLiteralContext): pass # Exit a parse tree produced by OpenSCENARIO2Parser#integerLiteral. - def exitIntegerLiteral(self, ctx:OpenSCENARIO2Parser.IntegerLiteralContext): + def exitIntegerLiteral(self, ctx: OpenSCENARIO2Parser.IntegerLiteralContext): pass - -del OpenSCENARIO2Parser \ No newline at end of file +del OpenSCENARIO2Parser diff --git a/scenario_execution/scenario_execution/osc2_parsing/OpenSCENARIO2Parser.py b/scenario_execution/scenario_execution/osc2_parsing/OpenSCENARIO2Parser.py index 9c5117a1..cf14910a 100644 --- a/scenario_execution/scenario_execution/osc2_parsing/OpenSCENARIO2Parser.py +++ b/scenario_execution/scenario_execution/osc2_parsing/OpenSCENARIO2Parser.py @@ -1,12 +1,28 @@ +# Copyright (C) 2024 Intel Corporation +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, +# software distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions +# and limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + # Generated from OpenSCENARIO2.g4 by ANTLR 4.9.1 # encoding: utf-8 from antlr4 import * from io import StringIO import sys if sys.version_info[1] > 5: - from typing import TextIO + from typing import TextIO else: - from typing.io import TextIO + from typing.io import TextIO def serializedATN(): @@ -655,63 +671,63 @@ def serializedATN(): return buf.getvalue() -class OpenSCENARIO2Parser ( Parser ): +class OpenSCENARIO2Parser (Parser): grammarFileName = "OpenSCENARIO2.g4" atn = ATNDeserializer().deserialize(serializedATN()) - decisionsToDFA = [ DFA(ds, i) for i, ds in enumerate(atn.decisionToState) ] + decisionsToDFA = [DFA(ds, i) for i, ds in enumerate(atn.decisionToState)] sharedContextCache = PredictionContextCache() - literalNames = [ "", "'import'", "'.'", "'type'", "'is'", "'SI'", - "'unit'", "'of'", "','", "':'", "'factor'", "'offset'", - "'kg'", "'m'", "'s'", "'A'", "'K'", "'mol'", "'cd'", - "'rad'", "'enum'", "'='", "'!'", "'=='", "'struct'", - "'inherits'", "'actor'", "'scenario'", "'action'", - "'modifier'", "'extend'", "'global'", "'list'", "'int'", - "'uint'", "'float'", "'bool'", "'string'", "'event'", - "'if'", "'@'", "'as'", "'rise'", "'fall'", "'elapsed'", - "'every'", "'var'", "'sample'", "'with'", "'keep'", - "'default'", "'hard'", "'remove_default'", "'on'", - "'do'", "'serial'", "'one_of'", "'parallel'", "'serial_no_memory'", - "'selector'", "'selector_no_memory'", "'wait'", "'emit'", - "'call'", "'until'", "'def'", "'->'", "'expression'", - "'undefined'", "'external'", "'only'", "'cover'", "'record'", - "'range'", "'?'", "'=>'", "'or'", "'and'", "'not'", - "'!='", "'<'", "'<='", "'>'", "'>='", "'in'", "'+'", - "'-'", "'*'", "'/'", "'%'", "'it'", "'..'", "", - "'['", "']'", "'('", "')'" ] - - symbolicNames = [ "", "", "", "", - "", "", "", "", - "", "", "", "", - "", "", "", "", - "", "", "", "", - "", "", "", "", - "", "", "", "", - "", "", "", "", - "", "", "", "", - "", "", "", "", - "", "", "", "", - "", "", "", "", - "", "", "", "", - "", "", "", "", - "", "", "", "", - "", "", "", "", - "", "", "", "", - "", "", "", "", - "", "", "", "", - "", "", "", "", - "", "", "", "", - "", "", "", "", - "", "", "", "", - "NEWLINE", "OPEN_BRACK", "CLOSE_BRACK", "OPEN_PAREN", - "CLOSE_PAREN", "SKIP_", "BLOCK_COMMENT", "LINE_COMMENT", - "StringLiteral", "FloatLiteral", "UintLiteral", "HexUintLiteral", - "IntLiteral", "BoolLiteral", "Identifier", "INDENT", - "DEDENT" ] + literalNames = ["", "'import'", "'.'", "'type'", "'is'", "'SI'", + "'unit'", "'of'", "','", "':'", "'factor'", "'offset'", + "'kg'", "'m'", "'s'", "'A'", "'K'", "'mol'", "'cd'", + "'rad'", "'enum'", "'='", "'!'", "'=='", "'struct'", + "'inherits'", "'actor'", "'scenario'", "'action'", + "'modifier'", "'extend'", "'global'", "'list'", "'int'", + "'uint'", "'float'", "'bool'", "'string'", "'event'", + "'if'", "'@'", "'as'", "'rise'", "'fall'", "'elapsed'", + "'every'", "'var'", "'sample'", "'with'", "'keep'", + "'default'", "'hard'", "'remove_default'", "'on'", + "'do'", "'serial'", "'one_of'", "'parallel'", "'serial_no_memory'", + "'selector'", "'selector_no_memory'", "'wait'", "'emit'", + "'call'", "'until'", "'def'", "'->'", "'expression'", + "'undefined'", "'external'", "'only'", "'cover'", "'record'", + "'range'", "'?'", "'=>'", "'or'", "'and'", "'not'", + "'!='", "'<'", "'<='", "'>'", "'>='", "'in'", "'+'", + "'-'", "'*'", "'/'", "'%'", "'it'", "'..'", "", + "'['", "']'", "'('", "')'"] + + symbolicNames = ["", "", "", "", + "", "", "", "", + "", "", "", "", + "", "", "", "", + "", "", "", "", + "", "", "", "", + "", "", "", "", + "", "", "", "", + "", "", "", "", + "", "", "", "", + "", "", "", "", + "", "", "", "", + "", "", "", "", + "", "", "", "", + "", "", "", "", + "", "", "", "", + "", "", "", "", + "", "", "", "", + "", "", "", "", + "", "", "", "", + "", "", "", "", + "", "", "", "", + "", "", "", "", + "NEWLINE", "OPEN_BRACK", "CLOSE_BRACK", "OPEN_PAREN", + "CLOSE_PAREN", "SKIP_", "BLOCK_COMMENT", "LINE_COMMENT", + "StringLiteral", "FloatLiteral", "UintLiteral", "HexUintLiteral", + "IntLiteral", "BoolLiteral", "Identifier", "INDENT", + "DEDENT"] RULE_osc_file = 0 RULE_preludeStatement = 1 @@ -854,234 +870,226 @@ class OpenSCENARIO2Parser ( Parser ): RULE_physicalLiteral = 138 RULE_integerLiteral = 139 - ruleNames = [ "osc_file", "preludeStatement", "importStatement", "importReference", - "structuredIdentifier", "oscDeclaration", "physicalTypeDeclaration", - "physicalTypeName", "baseUnitSpecifier", "sIBaseUnitSpecifier", - "unitDeclaration", "unitSpecifier", "unitName", "siBaseExponentList", - "siBaseExponent", "siUnitSpecifier", "siFactor", "siOffset", - "siBaseUnitName", "enumDeclaration", "enumMemberDecl", - "enumMemberValue", "enumName", "enumMemberName", "enumValueReference", - "inheritsCondition", "structDeclaration", "structInherits", - "structMemberDecl", "fieldName", "structName", "actorDeclaration", - "actorInherits", "actorMemberDecl", "actorName", "scenarioDeclaration", - "scenarioInherits", "scenarioMemberDecl", "qualifiedBehaviorName", - "behaviorName", "actionDeclaration", "actionInherits", - "modifierDeclaration", "modifierName", "typeExtension", - "enumTypeExtension", "structuredTypeExtension", "extendableTypeName", - "extensionMemberDecl", "globalParameterDeclaration", - "typeDeclarator", "nonAggregateTypeDeclarator", "aggregateTypeDeclarator", - "listTypeDeclarator", "primitiveType", "typeName", "eventDeclaration", - "eventSpecification", "eventReference", "eventFieldDecl", - "eventFieldName", "eventName", "eventPath", "eventCondition", - "riseExpression", "fallExpression", "elapsedExpression", - "everyExpression", "boolExpression", "durationExpression", - "fieldDeclaration", "parameterDeclaration", "variableDeclaration", - "sampleExpression", "defaultValue", "parameterWithDeclaration", - "parameterWithMember", "constraintDeclaration", "keepConstraintDeclaration", - "constraintQualifier", "constraintExpression", "removeDefaultDeclaration", - "parameterReference", "modifierInvocation", "behaviorExpression", - "behaviorSpecification", "onDirective", "onMember", "doDirective", - "doMember", "composition", "compositionOperator", "behaviorInvocation", - "behaviorWithDeclaration", "behaviorWithMember", "labelName", - "actorExpression", "waitDirective", "emitDirective", - "callDirective", "untilDirective", "methodInvocation", - "methodDeclaration", "returnType", "methodImplementation", - "methodQualifier", "methodName", "coverageDeclaration", - "coverDeclaration", "recordDeclaration", "coverageArgumentList", - "targetName", "expression", "ternaryOpExp", "implication", - "disjunction", "conjunction", "inversion", "relation", - "relationalOp", "sumExpression", "additiveOp", "term", - "multiplicativeOp", "factor", "postfixExp", "fieldAccess", - "primaryExp", "valueExp", "listConstructor", "rangeConstructor", - "identifierReference", "argumentListSpecification", "argumentSpecification", - "argumentName", "argumentList", "positionalArgument", - "namedArgument", "physicalLiteral", "integerLiteral" ] + ruleNames = ["osc_file", "preludeStatement", "importStatement", "importReference", + "structuredIdentifier", "oscDeclaration", "physicalTypeDeclaration", + "physicalTypeName", "baseUnitSpecifier", "sIBaseUnitSpecifier", + "unitDeclaration", "unitSpecifier", "unitName", "siBaseExponentList", + "siBaseExponent", "siUnitSpecifier", "siFactor", "siOffset", + "siBaseUnitName", "enumDeclaration", "enumMemberDecl", + "enumMemberValue", "enumName", "enumMemberName", "enumValueReference", + "inheritsCondition", "structDeclaration", "structInherits", + "structMemberDecl", "fieldName", "structName", "actorDeclaration", + "actorInherits", "actorMemberDecl", "actorName", "scenarioDeclaration", + "scenarioInherits", "scenarioMemberDecl", "qualifiedBehaviorName", + "behaviorName", "actionDeclaration", "actionInherits", + "modifierDeclaration", "modifierName", "typeExtension", + "enumTypeExtension", "structuredTypeExtension", "extendableTypeName", + "extensionMemberDecl", "globalParameterDeclaration", + "typeDeclarator", "nonAggregateTypeDeclarator", "aggregateTypeDeclarator", + "listTypeDeclarator", "primitiveType", "typeName", "eventDeclaration", + "eventSpecification", "eventReference", "eventFieldDecl", + "eventFieldName", "eventName", "eventPath", "eventCondition", + "riseExpression", "fallExpression", "elapsedExpression", + "everyExpression", "boolExpression", "durationExpression", + "fieldDeclaration", "parameterDeclaration", "variableDeclaration", + "sampleExpression", "defaultValue", "parameterWithDeclaration", + "parameterWithMember", "constraintDeclaration", "keepConstraintDeclaration", + "constraintQualifier", "constraintExpression", "removeDefaultDeclaration", + "parameterReference", "modifierInvocation", "behaviorExpression", + "behaviorSpecification", "onDirective", "onMember", "doDirective", + "doMember", "composition", "compositionOperator", "behaviorInvocation", + "behaviorWithDeclaration", "behaviorWithMember", "labelName", + "actorExpression", "waitDirective", "emitDirective", + "callDirective", "untilDirective", "methodInvocation", + "methodDeclaration", "returnType", "methodImplementation", + "methodQualifier", "methodName", "coverageDeclaration", + "coverDeclaration", "recordDeclaration", "coverageArgumentList", + "targetName", "expression", "ternaryOpExp", "implication", + "disjunction", "conjunction", "inversion", "relation", + "relationalOp", "sumExpression", "additiveOp", "term", + "multiplicativeOp", "factor", "postfixExp", "fieldAccess", + "primaryExp", "valueExp", "listConstructor", "rangeConstructor", + "identifierReference", "argumentListSpecification", "argumentSpecification", + "argumentName", "argumentList", "positionalArgument", + "namedArgument", "physicalLiteral", "integerLiteral"] EOF = Token.EOF - T__0=1 - T__1=2 - T__2=3 - T__3=4 - T__4=5 - T__5=6 - T__6=7 - T__7=8 - T__8=9 - T__9=10 - T__10=11 - T__11=12 - T__12=13 - T__13=14 - T__14=15 - T__15=16 - T__16=17 - T__17=18 - T__18=19 - T__19=20 - T__20=21 - T__21=22 - T__22=23 - T__23=24 - T__24=25 - T__25=26 - T__26=27 - T__27=28 - T__28=29 - T__29=30 - T__30=31 - T__31=32 - T__32=33 - T__33=34 - T__34=35 - T__35=36 - T__36=37 - T__37=38 - T__38=39 - T__39=40 - T__40=41 - T__41=42 - T__42=43 - T__43=44 - T__44=45 - T__45=46 - T__46=47 - T__47=48 - T__48=49 - T__49=50 - T__50=51 - T__51=52 - T__52=53 - T__53=54 - T__54=55 - T__55=56 - T__56=57 - T__57=58 - T__58=59 - T__59=60 - T__60=61 - T__61=62 - T__62=63 - T__63=64 - T__64=65 - T__65=66 - T__66=67 - T__67=68 - T__68=69 - T__69=70 - T__70=71 - T__71=72 - T__72=73 - T__73=74 - T__74=75 - T__75=76 - T__76=77 - T__77=78 - T__78=79 - T__79=80 - T__80=81 - T__81=82 - T__82=83 - T__83=84 - T__84=85 - T__85=86 - T__86=87 - T__87=88 - T__88=89 - T__89=90 - T__90=91 - NEWLINE=92 - OPEN_BRACK=93 - CLOSE_BRACK=94 - OPEN_PAREN=95 - CLOSE_PAREN=96 - SKIP_=97 - BLOCK_COMMENT=98 - LINE_COMMENT=99 - StringLiteral=100 - FloatLiteral=101 - UintLiteral=102 - HexUintLiteral=103 - IntLiteral=104 - BoolLiteral=105 - Identifier=106 - INDENT=107 - DEDENT=108 - - def __init__(self, input:TokenStream, output:TextIO = sys.stdout): + T__0 = 1 + T__1 = 2 + T__2 = 3 + T__3 = 4 + T__4 = 5 + T__5 = 6 + T__6 = 7 + T__7 = 8 + T__8 = 9 + T__9 = 10 + T__10 = 11 + T__11 = 12 + T__12 = 13 + T__13 = 14 + T__14 = 15 + T__15 = 16 + T__16 = 17 + T__17 = 18 + T__18 = 19 + T__19 = 20 + T__20 = 21 + T__21 = 22 + T__22 = 23 + T__23 = 24 + T__24 = 25 + T__25 = 26 + T__26 = 27 + T__27 = 28 + T__28 = 29 + T__29 = 30 + T__30 = 31 + T__31 = 32 + T__32 = 33 + T__33 = 34 + T__34 = 35 + T__35 = 36 + T__36 = 37 + T__37 = 38 + T__38 = 39 + T__39 = 40 + T__40 = 41 + T__41 = 42 + T__42 = 43 + T__43 = 44 + T__44 = 45 + T__45 = 46 + T__46 = 47 + T__47 = 48 + T__48 = 49 + T__49 = 50 + T__50 = 51 + T__51 = 52 + T__52 = 53 + T__53 = 54 + T__54 = 55 + T__55 = 56 + T__56 = 57 + T__57 = 58 + T__58 = 59 + T__59 = 60 + T__60 = 61 + T__61 = 62 + T__62 = 63 + T__63 = 64 + T__64 = 65 + T__65 = 66 + T__66 = 67 + T__67 = 68 + T__68 = 69 + T__69 = 70 + T__70 = 71 + T__71 = 72 + T__72 = 73 + T__73 = 74 + T__74 = 75 + T__75 = 76 + T__76 = 77 + T__77 = 78 + T__78 = 79 + T__79 = 80 + T__80 = 81 + T__81 = 82 + T__82 = 83 + T__83 = 84 + T__84 = 85 + T__85 = 86 + T__86 = 87 + T__87 = 88 + T__88 = 89 + T__89 = 90 + T__90 = 91 + NEWLINE = 92 + OPEN_BRACK = 93 + CLOSE_BRACK = 94 + OPEN_PAREN = 95 + CLOSE_PAREN = 96 + SKIP_ = 97 + BLOCK_COMMENT = 98 + LINE_COMMENT = 99 + StringLiteral = 100 + FloatLiteral = 101 + UintLiteral = 102 + HexUintLiteral = 103 + IntLiteral = 104 + BoolLiteral = 105 + Identifier = 106 + INDENT = 107 + DEDENT = 108 + + def __init__(self, input: TokenStream, output: TextIO = sys.stdout): super().__init__(input, output) self.checkVersion("4.9.1") self._interp = ParserATNSimulator(self, self.atn, self.decisionsToDFA, self.sharedContextCache) self._predicates = None - - - class Osc_fileContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def EOF(self): return self.getToken(OpenSCENARIO2Parser.EOF, 0) - def preludeStatement(self, i:int=None): + def preludeStatement(self, i: int = None): if i is None: return self.getTypedRuleContexts(OpenSCENARIO2Parser.PreludeStatementContext) else: - return self.getTypedRuleContext(OpenSCENARIO2Parser.PreludeStatementContext,i) + return self.getTypedRuleContext(OpenSCENARIO2Parser.PreludeStatementContext, i) - - def oscDeclaration(self, i:int=None): + def oscDeclaration(self, i: int = None): if i is None: return self.getTypedRuleContexts(OpenSCENARIO2Parser.OscDeclarationContext) else: - return self.getTypedRuleContext(OpenSCENARIO2Parser.OscDeclarationContext,i) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.OscDeclarationContext, i) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_osc_file - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterOsc_file" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterOsc_file"): listener.enterOsc_file(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitOsc_file" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitOsc_file"): listener.exitOsc_file(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitOsc_file" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitOsc_file"): return visitor.visitOsc_file(self) else: return visitor.visitChildren(self) - - - def osc_file(self): localctx = OpenSCENARIO2Parser.Osc_fileContext(self, self._ctx, self.state) self.enterRule(localctx, 0, self.RULE_osc_file) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 283 self._errHandler.sync(self) - _alt = self._interp.adaptivePredict(self._input,0,self._ctx) - while _alt!=2 and _alt!=ATN.INVALID_ALT_NUMBER: - if _alt==1: + _alt = self._interp.adaptivePredict(self._input, 0, self._ctx) + while _alt != 2 and _alt != ATN.INVALID_ALT_NUMBER: + if _alt == 1: self.state = 280 - self.preludeStatement() + self.preludeStatement() self.state = 285 self._errHandler.sync(self) - _alt = self._interp.adaptivePredict(self._input,0,self._ctx) + _alt = self._interp.adaptivePredict(self._input, 0, self._ctx) self.state = 289 self._errHandler.sync(self) _la = self._input.LA(1) - while (((_la) & ~0x3f) == 0 and ((1 << _la) & ((1 << OpenSCENARIO2Parser.T__2) | (1 << OpenSCENARIO2Parser.T__5) | (1 << OpenSCENARIO2Parser.T__19) | (1 << OpenSCENARIO2Parser.T__23) | (1 << OpenSCENARIO2Parser.T__25) | (1 << OpenSCENARIO2Parser.T__26) | (1 << OpenSCENARIO2Parser.T__27) | (1 << OpenSCENARIO2Parser.T__28) | (1 << OpenSCENARIO2Parser.T__29) | (1 << OpenSCENARIO2Parser.T__30))) != 0) or _la==OpenSCENARIO2Parser.NEWLINE: + while (((_la) & ~0x3f) == 0 and ((1 << _la) & ((1 << OpenSCENARIO2Parser.T__2) | (1 << OpenSCENARIO2Parser.T__5) | (1 << OpenSCENARIO2Parser.T__19) | (1 << OpenSCENARIO2Parser.T__23) | (1 << OpenSCENARIO2Parser.T__25) | (1 << OpenSCENARIO2Parser.T__26) | (1 << OpenSCENARIO2Parser.T__27) | (1 << OpenSCENARIO2Parser.T__28) | (1 << OpenSCENARIO2Parser.T__29) | (1 << OpenSCENARIO2Parser.T__30))) != 0) or _la == OpenSCENARIO2Parser.NEWLINE: self.state = 286 self.oscDeclaration() self.state = 291 @@ -1098,38 +1106,33 @@ def osc_file(self): self.exitRule() return localctx - class PreludeStatementContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def importStatement(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ImportStatementContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ImportStatementContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_preludeStatement - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterPreludeStatement" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterPreludeStatement"): listener.enterPreludeStatement(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitPreludeStatement" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitPreludeStatement"): listener.exitPreludeStatement(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitPreludeStatement" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitPreludeStatement"): return visitor.visitPreludeStatement(self) else: return visitor.visitChildren(self) - - - def preludeStatement(self): localctx = OpenSCENARIO2Parser.PreludeStatementContext(self, self._ctx, self.state) @@ -1146,17 +1149,15 @@ def preludeStatement(self): self.exitRule() return localctx - class ImportStatementContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def importReference(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ImportReferenceContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ImportReferenceContext, 0) def NEWLINE(self): return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) @@ -1164,23 +1165,20 @@ def NEWLINE(self): def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_importStatement - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterImportStatement" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterImportStatement"): listener.enterImportStatement(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitImportStatement" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitImportStatement"): listener.exitImportStatement(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitImportStatement" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitImportStatement"): return visitor.visitImportStatement(self) else: return visitor.visitChildren(self) - - - def importStatement(self): localctx = OpenSCENARIO2Parser.ImportStatementContext(self, self._ctx, self.state) @@ -1214,11 +1212,10 @@ def importStatement(self): self.exitRule() return localctx - class ImportReferenceContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser @@ -1226,29 +1223,25 @@ def StringLiteral(self): return self.getToken(OpenSCENARIO2Parser.StringLiteral, 0) def structuredIdentifier(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.StructuredIdentifierContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.StructuredIdentifierContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_importReference - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterImportReference" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterImportReference"): listener.enterImportReference(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitImportReference" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitImportReference"): listener.exitImportReference(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitImportReference" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitImportReference"): return visitor.visitImportReference(self) else: return visitor.visitChildren(self) - - - def importReference(self): localctx = OpenSCENARIO2Parser.ImportReferenceContext(self, self._ctx, self.state) @@ -1278,11 +1271,10 @@ def importReference(self): self.exitRule() return localctx - class StructuredIdentifierContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser @@ -1290,29 +1282,26 @@ def Identifier(self): return self.getToken(OpenSCENARIO2Parser.Identifier, 0) def structuredIdentifier(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.StructuredIdentifierContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.StructuredIdentifierContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_structuredIdentifier - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterStructuredIdentifier" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterStructuredIdentifier"): listener.enterStructuredIdentifier(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitStructuredIdentifier" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitStructuredIdentifier"): listener.exitStructuredIdentifier(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitStructuredIdentifier" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitStructuredIdentifier"): return visitor.visitStructuredIdentifier(self) else: return visitor.visitChildren(self) - - - def structuredIdentifier(self, _p:int=0): + def structuredIdentifier(self, _p: int = 0): _parentctx = self._ctx _parentState = self.state localctx = OpenSCENARIO2Parser.StructuredIdentifierContext(self, self._ctx, _parentState) @@ -1326,9 +1315,9 @@ def structuredIdentifier(self, _p:int=0): self._ctx.stop = self._input.LT(-1) self.state = 315 self._errHandler.sync(self) - _alt = self._interp.adaptivePredict(self._input,4,self._ctx) - while _alt!=2 and _alt!=ATN.INVALID_ALT_NUMBER: - if _alt==1: + _alt = self._interp.adaptivePredict(self._input, 4, self._ctx) + while _alt != 2 and _alt != ATN.INVALID_ALT_NUMBER: + if _alt == 1: if self._parseListeners is not None: self.triggerExitRuleEvent() _prevctx = localctx @@ -1341,10 +1330,10 @@ def structuredIdentifier(self, _p:int=0): self.state = 311 self.match(OpenSCENARIO2Parser.T__1) self.state = 312 - self.match(OpenSCENARIO2Parser.Identifier) + self.match(OpenSCENARIO2Parser.Identifier) self.state = 317 self._errHandler.sync(self) - _alt = self._interp.adaptivePredict(self._input,4,self._ctx) + _alt = self._interp.adaptivePredict(self._input, 4, self._ctx) except RecognitionException as re: localctx.exception = re @@ -1354,53 +1343,42 @@ def structuredIdentifier(self, _p:int=0): self.unrollRecursionContexts(_parentctx) return localctx - class OscDeclarationContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def physicalTypeDeclaration(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.PhysicalTypeDeclarationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.PhysicalTypeDeclarationContext, 0) def unitDeclaration(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.UnitDeclarationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.UnitDeclarationContext, 0) def enumDeclaration(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.EnumDeclarationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.EnumDeclarationContext, 0) def structDeclaration(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.StructDeclarationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.StructDeclarationContext, 0) def actorDeclaration(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ActorDeclarationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ActorDeclarationContext, 0) def actionDeclaration(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ActionDeclarationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ActionDeclarationContext, 0) def scenarioDeclaration(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ScenarioDeclarationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ScenarioDeclarationContext, 0) def modifierDeclaration(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ModifierDeclarationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ModifierDeclarationContext, 0) def typeExtension(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.TypeExtensionContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.TypeExtensionContext, 0) def globalParameterDeclaration(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.GlobalParameterDeclarationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.GlobalParameterDeclarationContext, 0) def NEWLINE(self): return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) @@ -1408,23 +1386,20 @@ def NEWLINE(self): def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_oscDeclaration - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterOscDeclaration" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterOscDeclaration"): listener.enterOscDeclaration(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitOscDeclaration" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitOscDeclaration"): listener.exitOscDeclaration(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitOscDeclaration" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitOscDeclaration"): return visitor.visitOscDeclaration(self) else: return visitor.visitChildren(self) - - - def oscDeclaration(self): localctx = OpenSCENARIO2Parser.OscDeclarationContext(self, self._ctx, self.state) @@ -1499,21 +1474,18 @@ def oscDeclaration(self): self.exitRule() return localctx - class PhysicalTypeDeclarationContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def physicalTypeName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.PhysicalTypeNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.PhysicalTypeNameContext, 0) def baseUnitSpecifier(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.BaseUnitSpecifierContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.BaseUnitSpecifierContext, 0) def NEWLINE(self): return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) @@ -1521,23 +1493,20 @@ def NEWLINE(self): def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_physicalTypeDeclaration - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterPhysicalTypeDeclaration" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterPhysicalTypeDeclaration"): listener.enterPhysicalTypeDeclaration(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitPhysicalTypeDeclaration" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitPhysicalTypeDeclaration"): listener.exitPhysicalTypeDeclaration(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitPhysicalTypeDeclaration" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitPhysicalTypeDeclaration"): return visitor.visitPhysicalTypeDeclaration(self) else: return visitor.visitChildren(self) - - - def physicalTypeDeclaration(self): localctx = OpenSCENARIO2Parser.PhysicalTypeDeclarationContext(self, self._ctx, self.state) @@ -1562,11 +1531,10 @@ def physicalTypeDeclaration(self): self.exitRule() return localctx - class PhysicalTypeNameContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser @@ -1576,23 +1544,20 @@ def Identifier(self): def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_physicalTypeName - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterPhysicalTypeName" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterPhysicalTypeName"): listener.enterPhysicalTypeName(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitPhysicalTypeName" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitPhysicalTypeName"): listener.exitPhysicalTypeName(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitPhysicalTypeName" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitPhysicalTypeName"): return visitor.visitPhysicalTypeName(self) else: return visitor.visitChildren(self) - - - def physicalTypeName(self): localctx = OpenSCENARIO2Parser.PhysicalTypeNameContext(self, self._ctx, self.state) @@ -1609,38 +1574,33 @@ def physicalTypeName(self): self.exitRule() return localctx - class BaseUnitSpecifierContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def sIBaseUnitSpecifier(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.SIBaseUnitSpecifierContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.SIBaseUnitSpecifierContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_baseUnitSpecifier - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterBaseUnitSpecifier" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterBaseUnitSpecifier"): listener.enterBaseUnitSpecifier(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitBaseUnitSpecifier" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitBaseUnitSpecifier"): listener.exitBaseUnitSpecifier(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitBaseUnitSpecifier" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitBaseUnitSpecifier"): return visitor.visitBaseUnitSpecifier(self) else: return visitor.visitChildren(self) - - - def baseUnitSpecifier(self): localctx = OpenSCENARIO2Parser.BaseUnitSpecifierContext(self, self._ctx, self.state) @@ -1657,11 +1617,10 @@ def baseUnitSpecifier(self): self.exitRule() return localctx - class SIBaseUnitSpecifierContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser @@ -1669,8 +1628,7 @@ def OPEN_PAREN(self): return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) def siBaseExponentList(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.SiBaseExponentListContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.SiBaseExponentListContext, 0) def CLOSE_PAREN(self): return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) @@ -1678,23 +1636,20 @@ def CLOSE_PAREN(self): def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_sIBaseUnitSpecifier - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterSIBaseUnitSpecifier" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterSIBaseUnitSpecifier"): listener.enterSIBaseUnitSpecifier(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitSIBaseUnitSpecifier" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitSIBaseUnitSpecifier"): listener.exitSIBaseUnitSpecifier(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitSIBaseUnitSpecifier" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitSIBaseUnitSpecifier"): return visitor.visitSIBaseUnitSpecifier(self) else: return visitor.visitChildren(self) - - - def sIBaseUnitSpecifier(self): localctx = OpenSCENARIO2Parser.SIBaseUnitSpecifierContext(self, self._ctx, self.state) @@ -1717,25 +1672,21 @@ def sIBaseUnitSpecifier(self): self.exitRule() return localctx - class UnitDeclarationContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def unitName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.UnitNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.UnitNameContext, 0) def physicalTypeName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.PhysicalTypeNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.PhysicalTypeNameContext, 0) def unitSpecifier(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.UnitSpecifierContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.UnitSpecifierContext, 0) def NEWLINE(self): return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) @@ -1743,23 +1694,20 @@ def NEWLINE(self): def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_unitDeclaration - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterUnitDeclaration" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterUnitDeclaration"): listener.enterUnitDeclaration(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitUnitDeclaration" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitUnitDeclaration"): listener.exitUnitDeclaration(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitUnitDeclaration" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitUnitDeclaration"): return visitor.visitUnitDeclaration(self) else: return visitor.visitChildren(self) - - - def unitDeclaration(self): localctx = OpenSCENARIO2Parser.UnitDeclarationContext(self, self._ctx, self.state) @@ -1788,38 +1736,33 @@ def unitDeclaration(self): self.exitRule() return localctx - class UnitSpecifierContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def siUnitSpecifier(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.SiUnitSpecifierContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.SiUnitSpecifierContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_unitSpecifier - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterUnitSpecifier" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterUnitSpecifier"): listener.enterUnitSpecifier(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitUnitSpecifier" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitUnitSpecifier"): listener.exitUnitSpecifier(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitUnitSpecifier" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitUnitSpecifier"): return visitor.visitUnitSpecifier(self) else: return visitor.visitChildren(self) - - - def unitSpecifier(self): localctx = OpenSCENARIO2Parser.UnitSpecifierContext(self, self._ctx, self.state) @@ -1836,11 +1779,10 @@ def unitSpecifier(self): self.exitRule() return localctx - class UnitNameContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser @@ -1848,29 +1790,25 @@ def Identifier(self): return self.getToken(OpenSCENARIO2Parser.Identifier, 0) def siBaseUnitName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.SiBaseUnitNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.SiBaseUnitNameContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_unitName - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterUnitName" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterUnitName"): listener.enterUnitName(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitUnitName" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitUnitName"): listener.exitUnitName(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitUnitName" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitUnitName"): return visitor.visitUnitName(self) else: return visitor.visitChildren(self) - - - def unitName(self): localctx = OpenSCENARIO2Parser.UnitNameContext(self, self._ctx, self.state) @@ -1900,41 +1838,36 @@ def unitName(self): self.exitRule() return localctx - class SiBaseExponentListContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser - def siBaseExponent(self, i:int=None): + def siBaseExponent(self, i: int = None): if i is None: return self.getTypedRuleContexts(OpenSCENARIO2Parser.SiBaseExponentContext) else: - return self.getTypedRuleContext(OpenSCENARIO2Parser.SiBaseExponentContext,i) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.SiBaseExponentContext, i) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_siBaseExponentList - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterSiBaseExponentList" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterSiBaseExponentList"): listener.enterSiBaseExponentList(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitSiBaseExponentList" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitSiBaseExponentList"): listener.exitSiBaseExponentList(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitSiBaseExponentList" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitSiBaseExponentList"): return visitor.visitSiBaseExponentList(self) else: return visitor.visitChildren(self) - - - def siBaseExponentList(self): localctx = OpenSCENARIO2Parser.SiBaseExponentListContext(self, self._ctx, self.state) @@ -1945,16 +1878,16 @@ def siBaseExponentList(self): self.siBaseExponent() self.state = 365 self._errHandler.sync(self) - _alt = self._interp.adaptivePredict(self._input,7,self._ctx) - while _alt!=2 and _alt!=ATN.INVALID_ALT_NUMBER: - if _alt==1: + _alt = self._interp.adaptivePredict(self._input, 7, self._ctx) + while _alt != 2 and _alt != ATN.INVALID_ALT_NUMBER: + if _alt == 1: self.state = 361 self.match(OpenSCENARIO2Parser.T__7) self.state = 362 - self.siBaseExponent() + self.siBaseExponent() self.state = 367 self._errHandler.sync(self) - _alt = self._interp.adaptivePredict(self._input,7,self._ctx) + _alt = self._interp.adaptivePredict(self._input, 7, self._ctx) except RecognitionException as re: localctx.exception = re @@ -1964,42 +1897,36 @@ def siBaseExponentList(self): self.exitRule() return localctx - class SiBaseExponentContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def siBaseUnitName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.SiBaseUnitNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.SiBaseUnitNameContext, 0) def integerLiteral(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.IntegerLiteralContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.IntegerLiteralContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_siBaseExponent - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterSiBaseExponent" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterSiBaseExponent"): listener.enterSiBaseExponent(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitSiBaseExponent" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitSiBaseExponent"): listener.exitSiBaseExponent(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitSiBaseExponent" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitSiBaseExponent"): return visitor.visitSiBaseExponent(self) else: return visitor.visitChildren(self) - - - def siBaseExponent(self): localctx = OpenSCENARIO2Parser.SiBaseExponentContext(self, self._ctx, self.state) @@ -2020,11 +1947,10 @@ def siBaseExponent(self): self.exitRule() return localctx - class SiUnitSpecifierContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser @@ -2032,45 +1958,39 @@ def OPEN_PAREN(self): return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) def siBaseExponentList(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.SiBaseExponentListContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.SiBaseExponentListContext, 0) def CLOSE_PAREN(self): return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) def siFactor(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.SiFactorContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.SiFactorContext, 0) def siOffset(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.SiOffsetContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.SiOffsetContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_siUnitSpecifier - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterSiUnitSpecifier" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterSiUnitSpecifier"): listener.enterSiUnitSpecifier(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitSiUnitSpecifier" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitSiUnitSpecifier"): listener.exitSiUnitSpecifier(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitSiUnitSpecifier" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitSiUnitSpecifier"): return visitor.visitSiUnitSpecifier(self) else: return visitor.visitChildren(self) - - - def siUnitSpecifier(self): localctx = OpenSCENARIO2Parser.SiUnitSpecifierContext(self, self._ctx, self.state) self.enterRule(localctx, 30, self.RULE_siUnitSpecifier) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 372 @@ -2081,24 +2001,22 @@ def siUnitSpecifier(self): self.siBaseExponentList() self.state = 377 self._errHandler.sync(self) - la_ = self._interp.adaptivePredict(self._input,8,self._ctx) + la_ = self._interp.adaptivePredict(self._input, 8, self._ctx) if la_ == 1: self.state = 375 self.match(OpenSCENARIO2Parser.T__7) self.state = 376 self.siFactor() - self.state = 381 self._errHandler.sync(self) _la = self._input.LA(1) - if _la==OpenSCENARIO2Parser.T__7: + if _la == OpenSCENARIO2Parser.T__7: self.state = 379 self.match(OpenSCENARIO2Parser.T__7) self.state = 380 self.siOffset() - self.state = 383 self.match(OpenSCENARIO2Parser.CLOSE_PAREN) except RecognitionException as re: @@ -2109,11 +2027,10 @@ def siUnitSpecifier(self): self.exitRule() return localctx - class SiFactorContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser @@ -2121,29 +2038,25 @@ def FloatLiteral(self): return self.getToken(OpenSCENARIO2Parser.FloatLiteral, 0) def integerLiteral(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.IntegerLiteralContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.IntegerLiteralContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_siFactor - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterSiFactor" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterSiFactor"): listener.enterSiFactor(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitSiFactor" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitSiFactor"): listener.exitSiFactor(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitSiFactor" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitSiFactor"): return visitor.visitSiFactor(self) else: return visitor.visitChildren(self) - - - def siFactor(self): localctx = OpenSCENARIO2Parser.SiFactorContext(self, self._ctx, self.state) @@ -2176,11 +2089,10 @@ def siFactor(self): self.exitRule() return localctx - class SiOffsetContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser @@ -2188,29 +2100,25 @@ def FloatLiteral(self): return self.getToken(OpenSCENARIO2Parser.FloatLiteral, 0) def integerLiteral(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.IntegerLiteralContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.IntegerLiteralContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_siOffset - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterSiOffset" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterSiOffset"): listener.enterSiOffset(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitSiOffset" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitSiOffset"): listener.exitSiOffset(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitSiOffset" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitSiOffset"): return visitor.visitSiOffset(self) else: return visitor.visitChildren(self) - - - def siOffset(self): localctx = OpenSCENARIO2Parser.SiOffsetContext(self, self._ctx, self.state) @@ -2243,40 +2151,35 @@ def siOffset(self): self.exitRule() return localctx - class SiBaseUnitNameContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser - def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_siBaseUnitName - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterSiBaseUnitName" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterSiBaseUnitName"): listener.enterSiBaseUnitName(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitSiBaseUnitName" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitSiBaseUnitName"): listener.exitSiBaseUnitName(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitSiBaseUnitName" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitSiBaseUnitName"): return visitor.visitSiBaseUnitName(self) else: return visitor.visitChildren(self) - - - def siBaseUnitName(self): localctx = OpenSCENARIO2Parser.SiBaseUnitNameContext(self, self._ctx, self.state) self.enterRule(localctx, 36, self.RULE_siBaseUnitName) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 397 @@ -2294,27 +2197,24 @@ def siBaseUnitName(self): self.exitRule() return localctx - class EnumDeclarationContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def enumName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.EnumNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.EnumNameContext, 0) def OPEN_BRACK(self): return self.getToken(OpenSCENARIO2Parser.OPEN_BRACK, 0) - def enumMemberDecl(self, i:int=None): + def enumMemberDecl(self, i: int = None): if i is None: return self.getTypedRuleContexts(OpenSCENARIO2Parser.EnumMemberDeclContext) else: - return self.getTypedRuleContext(OpenSCENARIO2Parser.EnumMemberDeclContext,i) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.EnumMemberDeclContext, i) def CLOSE_BRACK(self): return self.getToken(OpenSCENARIO2Parser.CLOSE_BRACK, 0) @@ -2325,28 +2225,25 @@ def NEWLINE(self): def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_enumDeclaration - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterEnumDeclaration" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterEnumDeclaration"): listener.enterEnumDeclaration(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitEnumDeclaration" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitEnumDeclaration"): listener.exitEnumDeclaration(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitEnumDeclaration" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitEnumDeclaration"): return visitor.visitEnumDeclaration(self) else: return visitor.visitChildren(self) - - - def enumDeclaration(self): localctx = OpenSCENARIO2Parser.EnumDeclarationContext(self, self._ctx, self.state) self.enterRule(localctx, 38, self.RULE_enumDeclaration) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 399 @@ -2362,7 +2259,7 @@ def enumDeclaration(self): self.state = 408 self._errHandler.sync(self) _la = self._input.LA(1) - while _la==OpenSCENARIO2Parser.T__7: + while _la == OpenSCENARIO2Parser.T__7: self.state = 404 self.match(OpenSCENARIO2Parser.T__7) self.state = 405 @@ -2383,47 +2280,41 @@ def enumDeclaration(self): self.exitRule() return localctx - class EnumMemberDeclContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def enumMemberName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.EnumMemberNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.EnumMemberNameContext, 0) def enumMemberValue(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.EnumMemberValueContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.EnumMemberValueContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_enumMemberDecl - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterEnumMemberDecl" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterEnumMemberDecl"): listener.enterEnumMemberDecl(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitEnumMemberDecl" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitEnumMemberDecl"): listener.exitEnumMemberDecl(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitEnumMemberDecl" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitEnumMemberDecl"): return visitor.visitEnumMemberDecl(self) else: return visitor.visitChildren(self) - - - def enumMemberDecl(self): localctx = OpenSCENARIO2Parser.EnumMemberDeclContext(self, self._ctx, self.state) self.enterRule(localctx, 40, self.RULE_enumMemberDecl) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 414 @@ -2431,13 +2322,12 @@ def enumMemberDecl(self): self.state = 417 self._errHandler.sync(self) _la = self._input.LA(1) - if _la==OpenSCENARIO2Parser.T__20: + if _la == OpenSCENARIO2Parser.T__20: self.state = 415 self.match(OpenSCENARIO2Parser.T__20) self.state = 416 self.enumMemberValue() - except RecognitionException as re: localctx.exception = re self._errHandler.reportError(self, re) @@ -2446,11 +2336,10 @@ def enumMemberDecl(self): self.exitRule() return localctx - class EnumMemberValueContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser @@ -2463,33 +2352,30 @@ def HexUintLiteral(self): def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_enumMemberValue - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterEnumMemberValue" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterEnumMemberValue"): listener.enterEnumMemberValue(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitEnumMemberValue" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitEnumMemberValue"): listener.exitEnumMemberValue(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitEnumMemberValue" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitEnumMemberValue"): return visitor.visitEnumMemberValue(self) else: return visitor.visitChildren(self) - - - def enumMemberValue(self): localctx = OpenSCENARIO2Parser.EnumMemberValueContext(self, self._ctx, self.state) self.enterRule(localctx, 42, self.RULE_enumMemberValue) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 419 _la = self._input.LA(1) - if not(_la==OpenSCENARIO2Parser.UintLiteral or _la==OpenSCENARIO2Parser.HexUintLiteral): + if not(_la == OpenSCENARIO2Parser.UintLiteral or _la == OpenSCENARIO2Parser.HexUintLiteral): self._errHandler.recoverInline(self) else: self._errHandler.reportMatch(self) @@ -2502,11 +2388,10 @@ def enumMemberValue(self): self.exitRule() return localctx - class EnumNameContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser @@ -2516,23 +2401,20 @@ def Identifier(self): def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_enumName - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterEnumName" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterEnumName"): listener.enterEnumName(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitEnumName" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitEnumName"): listener.exitEnumName(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitEnumName" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitEnumName"): return visitor.visitEnumName(self) else: return visitor.visitChildren(self) - - - def enumName(self): localctx = OpenSCENARIO2Parser.EnumNameContext(self, self._ctx, self.state) @@ -2549,11 +2431,10 @@ def enumName(self): self.exitRule() return localctx - class EnumMemberNameContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser @@ -2563,23 +2444,20 @@ def Identifier(self): def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_enumMemberName - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterEnumMemberName" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterEnumMemberName"): listener.enterEnumMemberName(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitEnumMemberName" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitEnumMemberName"): listener.exitEnumMemberName(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitEnumMemberName" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitEnumMemberName"): return visitor.visitEnumMemberName(self) else: return visitor.visitChildren(self) - - - def enumMemberName(self): localctx = OpenSCENARIO2Parser.EnumMemberNameContext(self, self._ctx, self.state) @@ -2596,42 +2474,36 @@ def enumMemberName(self): self.exitRule() return localctx - class EnumValueReferenceContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def enumName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.EnumNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.EnumNameContext, 0) def enumMemberName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.EnumMemberNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.EnumMemberNameContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_enumValueReference - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterEnumValueReference" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterEnumValueReference"): listener.enterEnumValueReference(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitEnumValueReference" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitEnumValueReference"): listener.exitEnumValueReference(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitEnumValueReference" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitEnumValueReference"): return visitor.visitEnumValueReference(self) else: return visitor.visitChildren(self) - - - def enumValueReference(self): localctx = OpenSCENARIO2Parser.EnumValueReferenceContext(self, self._ctx, self.state) @@ -2652,11 +2524,10 @@ def enumValueReference(self): self.exitRule() return localctx - class InheritsConditionContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser @@ -2664,15 +2535,13 @@ def OPEN_PAREN(self): return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) def fieldName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.FieldNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.FieldNameContext, 0) def CLOSE_PAREN(self): return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) def enumValueReference(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.EnumValueReferenceContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.EnumValueReferenceContext, 0) def BoolLiteral(self): return self.getToken(OpenSCENARIO2Parser.BoolLiteral, 0) @@ -2680,23 +2549,20 @@ def BoolLiteral(self): def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_inheritsCondition - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterInheritsCondition" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterInheritsCondition"): listener.enterInheritsCondition(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitInheritsCondition" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitInheritsCondition"): listener.exitInheritsCondition(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitInheritsCondition" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitInheritsCondition"): return visitor.visitInheritsCondition(self) else: return visitor.visitChildren(self) - - - def inheritsCondition(self): localctx = OpenSCENARIO2Parser.InheritsConditionContext(self, self._ctx, self.state) @@ -2733,24 +2599,21 @@ def inheritsCondition(self): self.exitRule() return localctx - class StructDeclarationContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def structName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.StructNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.StructNameContext, 0) def NEWLINE(self): return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) def structInherits(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.StructInheritsContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.StructInheritsContext, 0) def INDENT(self): return self.getToken(OpenSCENARIO2Parser.INDENT, 0) @@ -2758,38 +2621,34 @@ def INDENT(self): def DEDENT(self): return self.getToken(OpenSCENARIO2Parser.DEDENT, 0) - def structMemberDecl(self, i:int=None): + def structMemberDecl(self, i: int = None): if i is None: return self.getTypedRuleContexts(OpenSCENARIO2Parser.StructMemberDeclContext) else: - return self.getTypedRuleContext(OpenSCENARIO2Parser.StructMemberDeclContext,i) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.StructMemberDeclContext, i) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_structDeclaration - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterStructDeclaration" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterStructDeclaration"): listener.enterStructDeclaration(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitStructDeclaration" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitStructDeclaration"): listener.exitStructDeclaration(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitStructDeclaration" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitStructDeclaration"): return visitor.visitStructDeclaration(self) else: return visitor.visitChildren(self) - - - def structDeclaration(self): localctx = OpenSCENARIO2Parser.StructDeclarationContext(self, self._ctx, self.state) self.enterRule(localctx, 52, self.RULE_structDeclaration) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 438 @@ -2799,11 +2658,10 @@ def structDeclaration(self): self.state = 441 self._errHandler.sync(self) _la = self._input.LA(1) - if _la==OpenSCENARIO2Parser.T__24: + if _la == OpenSCENARIO2Parser.T__24: self.state = 440 self.structInherits() - self.state = 454 self._errHandler.sync(self) token = self._input.LA(1) @@ -2814,13 +2672,13 @@ def structDeclaration(self): self.match(OpenSCENARIO2Parser.NEWLINE) self.state = 445 self.match(OpenSCENARIO2Parser.INDENT) - self.state = 447 + self.state = 447 self._errHandler.sync(self) _la = self._input.LA(1) while True: self.state = 446 self.structMemberDecl() - self.state = 449 + self.state = 449 self._errHandler.sync(self) _la = self._input.LA(1) if not ((((_la) & ~0x3f) == 0 and ((1 << _la) & ((1 << OpenSCENARIO2Parser.T__37) | (1 << OpenSCENARIO2Parser.T__45) | (1 << OpenSCENARIO2Parser.T__48) | (1 << OpenSCENARIO2Parser.T__51))) != 0) or ((((_la - 65)) & ~0x3f) == 0 and ((1 << (_la - 65)) & ((1 << (OpenSCENARIO2Parser.T__64 - 65)) | (1 << (OpenSCENARIO2Parser.T__70 - 65)) | (1 << (OpenSCENARIO2Parser.T__71 - 65)) | (1 << (OpenSCENARIO2Parser.Identifier - 65)))) != 0)): @@ -2844,47 +2702,41 @@ def structDeclaration(self): self.exitRule() return localctx - class StructInheritsContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def structName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.StructNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.StructNameContext, 0) def inheritsCondition(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.InheritsConditionContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.InheritsConditionContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_structInherits - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterStructInherits" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterStructInherits"): listener.enterStructInherits(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitStructInherits" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitStructInherits"): listener.exitStructInherits(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitStructInherits" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitStructInherits"): return visitor.visitStructInherits(self) else: return visitor.visitChildren(self) - - - def structInherits(self): localctx = OpenSCENARIO2Parser.StructInheritsContext(self, self._ctx, self.state) self.enterRule(localctx, 54, self.RULE_structInherits) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 456 @@ -2894,11 +2746,10 @@ def structInherits(self): self.state = 459 self._errHandler.sync(self) _la = self._input.LA(1) - if _la==OpenSCENARIO2Parser.OPEN_PAREN: + if _la == OpenSCENARIO2Parser.OPEN_PAREN: self.state = 458 self.inheritsCondition() - except RecognitionException as re: localctx.exception = re self._errHandler.reportError(self, re) @@ -2907,54 +2758,45 @@ def structInherits(self): self.exitRule() return localctx - class StructMemberDeclContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def eventDeclaration(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.EventDeclarationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.EventDeclarationContext, 0) def fieldDeclaration(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.FieldDeclarationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.FieldDeclarationContext, 0) def constraintDeclaration(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ConstraintDeclarationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ConstraintDeclarationContext, 0) def methodDeclaration(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.MethodDeclarationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.MethodDeclarationContext, 0) def coverageDeclaration(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.CoverageDeclarationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.CoverageDeclarationContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_structMemberDecl - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterStructMemberDecl" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterStructMemberDecl"): listener.enterStructMemberDecl(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitStructMemberDecl" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitStructMemberDecl"): listener.exitStructMemberDecl(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitStructMemberDecl" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitStructMemberDecl"): return visitor.visitStructMemberDecl(self) else: return visitor.visitChildren(self) - - - def structMemberDecl(self): localctx = OpenSCENARIO2Parser.StructMemberDeclContext(self, self._ctx, self.state) @@ -2999,11 +2841,10 @@ def structMemberDecl(self): self.exitRule() return localctx - class FieldNameContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser @@ -3013,23 +2854,20 @@ def Identifier(self): def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_fieldName - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterFieldName" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterFieldName"): listener.enterFieldName(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitFieldName" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitFieldName"): listener.exitFieldName(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitFieldName" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitFieldName"): return visitor.visitFieldName(self) else: return visitor.visitChildren(self) - - - def fieldName(self): localctx = OpenSCENARIO2Parser.FieldNameContext(self, self._ctx, self.state) @@ -3046,11 +2884,10 @@ def fieldName(self): self.exitRule() return localctx - class StructNameContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser @@ -3060,23 +2897,20 @@ def Identifier(self): def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_structName - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterStructName" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterStructName"): listener.enterStructName(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitStructName" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitStructName"): listener.exitStructName(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitStructName" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitStructName"): return visitor.visitStructName(self) else: return visitor.visitChildren(self) - - - def structName(self): localctx = OpenSCENARIO2Parser.StructNameContext(self, self._ctx, self.state) @@ -3093,24 +2927,21 @@ def structName(self): self.exitRule() return localctx - class ActorDeclarationContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def actorName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ActorNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ActorNameContext, 0) def NEWLINE(self): return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) def actorInherits(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ActorInheritsContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ActorInheritsContext, 0) def INDENT(self): return self.getToken(OpenSCENARIO2Parser.INDENT, 0) @@ -3118,38 +2949,34 @@ def INDENT(self): def DEDENT(self): return self.getToken(OpenSCENARIO2Parser.DEDENT, 0) - def actorMemberDecl(self, i:int=None): + def actorMemberDecl(self, i: int = None): if i is None: return self.getTypedRuleContexts(OpenSCENARIO2Parser.ActorMemberDeclContext) else: - return self.getTypedRuleContext(OpenSCENARIO2Parser.ActorMemberDeclContext,i) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ActorMemberDeclContext, i) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_actorDeclaration - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterActorDeclaration" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterActorDeclaration"): listener.enterActorDeclaration(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitActorDeclaration" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitActorDeclaration"): listener.exitActorDeclaration(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitActorDeclaration" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitActorDeclaration"): return visitor.visitActorDeclaration(self) else: return visitor.visitChildren(self) - - - def actorDeclaration(self): localctx = OpenSCENARIO2Parser.ActorDeclarationContext(self, self._ctx, self.state) self.enterRule(localctx, 62, self.RULE_actorDeclaration) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 472 @@ -3159,11 +2986,10 @@ def actorDeclaration(self): self.state = 475 self._errHandler.sync(self) _la = self._input.LA(1) - if _la==OpenSCENARIO2Parser.T__24: + if _la == OpenSCENARIO2Parser.T__24: self.state = 474 self.actorInherits() - self.state = 488 self._errHandler.sync(self) token = self._input.LA(1) @@ -3174,13 +3000,13 @@ def actorDeclaration(self): self.match(OpenSCENARIO2Parser.NEWLINE) self.state = 479 self.match(OpenSCENARIO2Parser.INDENT) - self.state = 481 + self.state = 481 self._errHandler.sync(self) _la = self._input.LA(1) while True: self.state = 480 self.actorMemberDecl() - self.state = 483 + self.state = 483 self._errHandler.sync(self) _la = self._input.LA(1) if not ((((_la) & ~0x3f) == 0 and ((1 << _la) & ((1 << OpenSCENARIO2Parser.T__37) | (1 << OpenSCENARIO2Parser.T__45) | (1 << OpenSCENARIO2Parser.T__48) | (1 << OpenSCENARIO2Parser.T__51))) != 0) or ((((_la - 65)) & ~0x3f) == 0 and ((1 << (_la - 65)) & ((1 << (OpenSCENARIO2Parser.T__64 - 65)) | (1 << (OpenSCENARIO2Parser.T__70 - 65)) | (1 << (OpenSCENARIO2Parser.T__71 - 65)) | (1 << (OpenSCENARIO2Parser.Identifier - 65)))) != 0)): @@ -3204,47 +3030,41 @@ def actorDeclaration(self): self.exitRule() return localctx - class ActorInheritsContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def actorName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ActorNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ActorNameContext, 0) def inheritsCondition(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.InheritsConditionContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.InheritsConditionContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_actorInherits - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterActorInherits" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterActorInherits"): listener.enterActorInherits(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitActorInherits" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitActorInherits"): listener.exitActorInherits(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitActorInherits" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitActorInherits"): return visitor.visitActorInherits(self) else: return visitor.visitChildren(self) - - - def actorInherits(self): localctx = OpenSCENARIO2Parser.ActorInheritsContext(self, self._ctx, self.state) self.enterRule(localctx, 64, self.RULE_actorInherits) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 490 @@ -3254,11 +3074,10 @@ def actorInherits(self): self.state = 493 self._errHandler.sync(self) _la = self._input.LA(1) - if _la==OpenSCENARIO2Parser.OPEN_PAREN: + if _la == OpenSCENARIO2Parser.OPEN_PAREN: self.state = 492 self.inheritsCondition() - except RecognitionException as re: localctx.exception = re self._errHandler.reportError(self, re) @@ -3267,54 +3086,45 @@ def actorInherits(self): self.exitRule() return localctx - class ActorMemberDeclContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def eventDeclaration(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.EventDeclarationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.EventDeclarationContext, 0) def fieldDeclaration(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.FieldDeclarationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.FieldDeclarationContext, 0) def constraintDeclaration(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ConstraintDeclarationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ConstraintDeclarationContext, 0) def methodDeclaration(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.MethodDeclarationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.MethodDeclarationContext, 0) def coverageDeclaration(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.CoverageDeclarationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.CoverageDeclarationContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_actorMemberDecl - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterActorMemberDecl" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterActorMemberDecl"): listener.enterActorMemberDecl(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitActorMemberDecl" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitActorMemberDecl"): listener.exitActorMemberDecl(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitActorMemberDecl" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitActorMemberDecl"): return visitor.visitActorMemberDecl(self) else: return visitor.visitChildren(self) - - - def actorMemberDecl(self): localctx = OpenSCENARIO2Parser.ActorMemberDeclContext(self, self._ctx, self.state) @@ -3359,11 +3169,10 @@ def actorMemberDecl(self): self.exitRule() return localctx - class ActorNameContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser @@ -3373,23 +3182,20 @@ def Identifier(self): def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_actorName - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterActorName" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterActorName"): listener.enterActorName(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitActorName" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitActorName"): listener.exitActorName(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitActorName" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitActorName"): return visitor.visitActorName(self) else: return visitor.visitChildren(self) - - - def actorName(self): localctx = OpenSCENARIO2Parser.ActorNameContext(self, self._ctx, self.state) @@ -3406,24 +3212,21 @@ def actorName(self): self.exitRule() return localctx - class ScenarioDeclarationContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def qualifiedBehaviorName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.QualifiedBehaviorNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.QualifiedBehaviorNameContext, 0) def NEWLINE(self): return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) def scenarioInherits(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ScenarioInheritsContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ScenarioInheritsContext, 0) def INDENT(self): return self.getToken(OpenSCENARIO2Parser.INDENT, 0) @@ -3431,45 +3234,40 @@ def INDENT(self): def DEDENT(self): return self.getToken(OpenSCENARIO2Parser.DEDENT, 0) - def scenarioMemberDecl(self, i:int=None): + def scenarioMemberDecl(self, i: int = None): if i is None: return self.getTypedRuleContexts(OpenSCENARIO2Parser.ScenarioMemberDeclContext) else: - return self.getTypedRuleContext(OpenSCENARIO2Parser.ScenarioMemberDeclContext,i) + return self.getTypedRuleContext(OpenSCENARIO2Parser.ScenarioMemberDeclContext, i) - - def behaviorSpecification(self, i:int=None): + def behaviorSpecification(self, i: int = None): if i is None: return self.getTypedRuleContexts(OpenSCENARIO2Parser.BehaviorSpecificationContext) else: - return self.getTypedRuleContext(OpenSCENARIO2Parser.BehaviorSpecificationContext,i) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.BehaviorSpecificationContext, i) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_scenarioDeclaration - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterScenarioDeclaration" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterScenarioDeclaration"): listener.enterScenarioDeclaration(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitScenarioDeclaration" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitScenarioDeclaration"): listener.exitScenarioDeclaration(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitScenarioDeclaration" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitScenarioDeclaration"): return visitor.visitScenarioDeclaration(self) else: return visitor.visitChildren(self) - - - def scenarioDeclaration(self): localctx = OpenSCENARIO2Parser.ScenarioDeclarationContext(self, self._ctx, self.state) self.enterRule(localctx, 70, self.RULE_scenarioDeclaration) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 504 @@ -3479,11 +3277,10 @@ def scenarioDeclaration(self): self.state = 507 self._errHandler.sync(self) _la = self._input.LA(1) - if _la==OpenSCENARIO2Parser.T__24: + if _la == OpenSCENARIO2Parser.T__24: self.state = 506 self.scenarioInherits() - self.state = 521 self._errHandler.sync(self) token = self._input.LA(1) @@ -3494,7 +3291,7 @@ def scenarioDeclaration(self): self.match(OpenSCENARIO2Parser.NEWLINE) self.state = 511 self.match(OpenSCENARIO2Parser.INDENT) - self.state = 514 + self.state = 514 self._errHandler.sync(self) _la = self._input.LA(1) while True: @@ -3512,7 +3309,7 @@ def scenarioDeclaration(self): else: raise NoViableAltException(self) - self.state = 516 + self.state = 516 self._errHandler.sync(self) _la = self._input.LA(1) if not ((((_la) & ~0x3f) == 0 and ((1 << _la) & ((1 << OpenSCENARIO2Parser.T__37) | (1 << OpenSCENARIO2Parser.T__45) | (1 << OpenSCENARIO2Parser.T__48) | (1 << OpenSCENARIO2Parser.T__51) | (1 << OpenSCENARIO2Parser.T__52) | (1 << OpenSCENARIO2Parser.T__53))) != 0) or ((((_la - 65)) & ~0x3f) == 0 and ((1 << (_la - 65)) & ((1 << (OpenSCENARIO2Parser.T__64 - 65)) | (1 << (OpenSCENARIO2Parser.T__70 - 65)) | (1 << (OpenSCENARIO2Parser.T__71 - 65)) | (1 << (OpenSCENARIO2Parser.Identifier - 65)))) != 0)): @@ -3536,47 +3333,41 @@ def scenarioDeclaration(self): self.exitRule() return localctx - class ScenarioInheritsContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def qualifiedBehaviorName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.QualifiedBehaviorNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.QualifiedBehaviorNameContext, 0) def inheritsCondition(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.InheritsConditionContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.InheritsConditionContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_scenarioInherits - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterScenarioInherits" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterScenarioInherits"): listener.enterScenarioInherits(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitScenarioInherits" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitScenarioInherits"): listener.exitScenarioInherits(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitScenarioInherits" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitScenarioInherits"): return visitor.visitScenarioInherits(self) else: return visitor.visitChildren(self) - - - def scenarioInherits(self): localctx = OpenSCENARIO2Parser.ScenarioInheritsContext(self, self._ctx, self.state) self.enterRule(localctx, 72, self.RULE_scenarioInherits) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 523 @@ -3586,11 +3377,10 @@ def scenarioInherits(self): self.state = 526 self._errHandler.sync(self) _la = self._input.LA(1) - if _la==OpenSCENARIO2Parser.OPEN_PAREN: + if _la == OpenSCENARIO2Parser.OPEN_PAREN: self.state = 525 self.inheritsCondition() - except RecognitionException as re: localctx.exception = re self._errHandler.reportError(self, re) @@ -3599,58 +3389,48 @@ def scenarioInherits(self): self.exitRule() return localctx - class ScenarioMemberDeclContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def eventDeclaration(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.EventDeclarationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.EventDeclarationContext, 0) def fieldDeclaration(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.FieldDeclarationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.FieldDeclarationContext, 0) def constraintDeclaration(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ConstraintDeclarationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ConstraintDeclarationContext, 0) def methodDeclaration(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.MethodDeclarationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.MethodDeclarationContext, 0) def coverageDeclaration(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.CoverageDeclarationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.CoverageDeclarationContext, 0) def modifierInvocation(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ModifierInvocationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ModifierInvocationContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_scenarioMemberDecl - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterScenarioMemberDecl" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterScenarioMemberDecl"): listener.enterScenarioMemberDecl(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitScenarioMemberDecl" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitScenarioMemberDecl"): listener.exitScenarioMemberDecl(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitScenarioMemberDecl" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitScenarioMemberDecl"): return visitor.visitScenarioMemberDecl(self) else: return visitor.visitChildren(self) - - - def scenarioMemberDecl(self): localctx = OpenSCENARIO2Parser.ScenarioMemberDeclContext(self, self._ctx, self.state) @@ -3658,7 +3438,7 @@ def scenarioMemberDecl(self): try: self.state = 534 self._errHandler.sync(self) - la_ = self._interp.adaptivePredict(self._input,30,self._ctx) + la_ = self._interp.adaptivePredict(self._input, 30, self._ctx) if la_ == 1: self.enterOuterAlt(localctx, 1) self.state = 528 @@ -3695,7 +3475,6 @@ def scenarioMemberDecl(self): self.modifierInvocation() pass - except RecognitionException as re: localctx.exception = re self._errHandler.reportError(self, re) @@ -3704,42 +3483,36 @@ def scenarioMemberDecl(self): self.exitRule() return localctx - class QualifiedBehaviorNameContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def behaviorName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.BehaviorNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.BehaviorNameContext, 0) def actorName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ActorNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ActorNameContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_qualifiedBehaviorName - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterQualifiedBehaviorName" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterQualifiedBehaviorName"): listener.enterQualifiedBehaviorName(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitQualifiedBehaviorName" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitQualifiedBehaviorName"): listener.exitQualifiedBehaviorName(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitQualifiedBehaviorName" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitQualifiedBehaviorName"): return visitor.visitQualifiedBehaviorName(self) else: return visitor.visitChildren(self) - - - def qualifiedBehaviorName(self): localctx = OpenSCENARIO2Parser.QualifiedBehaviorNameContext(self, self._ctx, self.state) @@ -3748,14 +3521,13 @@ def qualifiedBehaviorName(self): self.enterOuterAlt(localctx, 1) self.state = 539 self._errHandler.sync(self) - la_ = self._interp.adaptivePredict(self._input,31,self._ctx) + la_ = self._interp.adaptivePredict(self._input, 31, self._ctx) if la_ == 1: self.state = 536 self.actorName() self.state = 537 self.match(OpenSCENARIO2Parser.T__1) - self.state = 541 self.behaviorName() except RecognitionException as re: @@ -3766,11 +3538,10 @@ def qualifiedBehaviorName(self): self.exitRule() return localctx - class BehaviorNameContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser @@ -3780,23 +3551,20 @@ def Identifier(self): def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_behaviorName - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterBehaviorName" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterBehaviorName"): listener.enterBehaviorName(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitBehaviorName" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitBehaviorName"): listener.exitBehaviorName(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitBehaviorName" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitBehaviorName"): return visitor.visitBehaviorName(self) else: return visitor.visitChildren(self) - - - def behaviorName(self): localctx = OpenSCENARIO2Parser.BehaviorNameContext(self, self._ctx, self.state) @@ -3813,24 +3581,21 @@ def behaviorName(self): self.exitRule() return localctx - class ActionDeclarationContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def qualifiedBehaviorName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.QualifiedBehaviorNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.QualifiedBehaviorNameContext, 0) def NEWLINE(self): return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) def actionInherits(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ActionInheritsContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ActionInheritsContext, 0) def INDENT(self): return self.getToken(OpenSCENARIO2Parser.INDENT, 0) @@ -3838,45 +3603,40 @@ def INDENT(self): def DEDENT(self): return self.getToken(OpenSCENARIO2Parser.DEDENT, 0) - def scenarioMemberDecl(self, i:int=None): + def scenarioMemberDecl(self, i: int = None): if i is None: return self.getTypedRuleContexts(OpenSCENARIO2Parser.ScenarioMemberDeclContext) else: - return self.getTypedRuleContext(OpenSCENARIO2Parser.ScenarioMemberDeclContext,i) + return self.getTypedRuleContext(OpenSCENARIO2Parser.ScenarioMemberDeclContext, i) - - def behaviorSpecification(self, i:int=None): + def behaviorSpecification(self, i: int = None): if i is None: return self.getTypedRuleContexts(OpenSCENARIO2Parser.BehaviorSpecificationContext) else: - return self.getTypedRuleContext(OpenSCENARIO2Parser.BehaviorSpecificationContext,i) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.BehaviorSpecificationContext, i) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_actionDeclaration - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterActionDeclaration" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterActionDeclaration"): listener.enterActionDeclaration(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitActionDeclaration" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitActionDeclaration"): listener.exitActionDeclaration(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitActionDeclaration" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitActionDeclaration"): return visitor.visitActionDeclaration(self) else: return visitor.visitChildren(self) - - - - def actionDeclaration(self): + def actionDeclaration(self): localctx = OpenSCENARIO2Parser.ActionDeclarationContext(self, self._ctx, self.state) self.enterRule(localctx, 80, self.RULE_actionDeclaration) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 545 @@ -3886,11 +3646,10 @@ def actionDeclaration(self): self.state = 548 self._errHandler.sync(self) _la = self._input.LA(1) - if _la==OpenSCENARIO2Parser.T__24: + if _la == OpenSCENARIO2Parser.T__24: self.state = 547 self.actionInherits() - self.state = 562 self._errHandler.sync(self) token = self._input.LA(1) @@ -3901,7 +3660,7 @@ def actionDeclaration(self): self.match(OpenSCENARIO2Parser.NEWLINE) self.state = 552 self.match(OpenSCENARIO2Parser.INDENT) - self.state = 555 + self.state = 555 self._errHandler.sync(self) _la = self._input.LA(1) while True: @@ -3919,7 +3678,7 @@ def actionDeclaration(self): else: raise NoViableAltException(self) - self.state = 557 + self.state = 557 self._errHandler.sync(self) _la = self._input.LA(1) if not ((((_la) & ~0x3f) == 0 and ((1 << _la) & ((1 << OpenSCENARIO2Parser.T__37) | (1 << OpenSCENARIO2Parser.T__45) | (1 << OpenSCENARIO2Parser.T__48) | (1 << OpenSCENARIO2Parser.T__51) | (1 << OpenSCENARIO2Parser.T__52) | (1 << OpenSCENARIO2Parser.T__53))) != 0) or ((((_la - 65)) & ~0x3f) == 0 and ((1 << (_la - 65)) & ((1 << (OpenSCENARIO2Parser.T__64 - 65)) | (1 << (OpenSCENARIO2Parser.T__70 - 65)) | (1 << (OpenSCENARIO2Parser.T__71 - 65)) | (1 << (OpenSCENARIO2Parser.Identifier - 65)))) != 0)): @@ -3943,47 +3702,41 @@ def actionDeclaration(self): self.exitRule() return localctx - class ActionInheritsContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def qualifiedBehaviorName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.QualifiedBehaviorNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.QualifiedBehaviorNameContext, 0) def inheritsCondition(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.InheritsConditionContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.InheritsConditionContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_actionInherits - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterActionInherits" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterActionInherits"): listener.enterActionInherits(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitActionInherits" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitActionInherits"): listener.exitActionInherits(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitActionInherits" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitActionInherits"): return visitor.visitActionInherits(self) else: return visitor.visitChildren(self) - - - def actionInherits(self): localctx = OpenSCENARIO2Parser.ActionInheritsContext(self, self._ctx, self.state) self.enterRule(localctx, 82, self.RULE_actionInherits) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 564 @@ -3993,11 +3746,10 @@ def actionInherits(self): self.state = 567 self._errHandler.sync(self) _la = self._input.LA(1) - if _la==OpenSCENARIO2Parser.OPEN_PAREN: + if _la == OpenSCENARIO2Parser.OPEN_PAREN: self.state = 566 self.inheritsCondition() - except RecognitionException as re: localctx.exception = re self._errHandler.reportError(self, re) @@ -4006,28 +3758,24 @@ def actionInherits(self): self.exitRule() return localctx - class ModifierDeclarationContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def modifierName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ModifierNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ModifierNameContext, 0) def NEWLINE(self): return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) def actorName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ActorNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ActorNameContext, 0) def qualifiedBehaviorName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.QualifiedBehaviorNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.QualifiedBehaviorNameContext, 0) def INDENT(self): return self.getToken(OpenSCENARIO2Parser.INDENT, 0) @@ -4035,64 +3783,58 @@ def INDENT(self): def DEDENT(self): return self.getToken(OpenSCENARIO2Parser.DEDENT, 0) - def scenarioMemberDecl(self, i:int=None): + def scenarioMemberDecl(self, i: int = None): if i is None: return self.getTypedRuleContexts(OpenSCENARIO2Parser.ScenarioMemberDeclContext) else: - return self.getTypedRuleContext(OpenSCENARIO2Parser.ScenarioMemberDeclContext,i) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ScenarioMemberDeclContext, i) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_modifierDeclaration - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterModifierDeclaration" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterModifierDeclaration"): listener.enterModifierDeclaration(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitModifierDeclaration" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitModifierDeclaration"): listener.exitModifierDeclaration(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitModifierDeclaration" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitModifierDeclaration"): return visitor.visitModifierDeclaration(self) else: return visitor.visitChildren(self) - - - def modifierDeclaration(self): localctx = OpenSCENARIO2Parser.ModifierDeclarationContext(self, self._ctx, self.state) self.enterRule(localctx, 84, self.RULE_modifierDeclaration) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 569 self.match(OpenSCENARIO2Parser.T__28) self.state = 573 self._errHandler.sync(self) - la_ = self._interp.adaptivePredict(self._input,37,self._ctx) + la_ = self._interp.adaptivePredict(self._input, 37, self._ctx) if la_ == 1: self.state = 570 self.actorName() self.state = 571 self.match(OpenSCENARIO2Parser.T__1) - self.state = 575 self.modifierName() self.state = 578 self._errHandler.sync(self) _la = self._input.LA(1) - if _la==OpenSCENARIO2Parser.T__6: + if _la == OpenSCENARIO2Parser.T__6: self.state = 576 self.match(OpenSCENARIO2Parser.T__6) self.state = 577 self.qualifiedBehaviorName() - self.state = 591 self._errHandler.sync(self) token = self._input.LA(1) @@ -4103,13 +3845,13 @@ def modifierDeclaration(self): self.match(OpenSCENARIO2Parser.NEWLINE) self.state = 582 self.match(OpenSCENARIO2Parser.INDENT) - self.state = 584 + self.state = 584 self._errHandler.sync(self) _la = self._input.LA(1) while True: self.state = 583 self.scenarioMemberDecl() - self.state = 586 + self.state = 586 self._errHandler.sync(self) _la = self._input.LA(1) if not ((((_la) & ~0x3f) == 0 and ((1 << _la) & ((1 << OpenSCENARIO2Parser.T__37) | (1 << OpenSCENARIO2Parser.T__45) | (1 << OpenSCENARIO2Parser.T__48) | (1 << OpenSCENARIO2Parser.T__51))) != 0) or ((((_la - 65)) & ~0x3f) == 0 and ((1 << (_la - 65)) & ((1 << (OpenSCENARIO2Parser.T__64 - 65)) | (1 << (OpenSCENARIO2Parser.T__70 - 65)) | (1 << (OpenSCENARIO2Parser.T__71 - 65)) | (1 << (OpenSCENARIO2Parser.Identifier - 65)))) != 0)): @@ -4133,11 +3875,10 @@ def modifierDeclaration(self): self.exitRule() return localctx - class ModifierNameContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser @@ -4147,23 +3888,20 @@ def Identifier(self): def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_modifierName - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterModifierName" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterModifierName"): listener.enterModifierName(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitModifierName" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitModifierName"): listener.exitModifierName(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitModifierName" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitModifierName"): return visitor.visitModifierName(self) else: return visitor.visitChildren(self) - - - def modifierName(self): localctx = OpenSCENARIO2Parser.ModifierNameContext(self, self._ctx, self.state) @@ -4180,42 +3918,36 @@ def modifierName(self): self.exitRule() return localctx - class TypeExtensionContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def enumTypeExtension(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.EnumTypeExtensionContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.EnumTypeExtensionContext, 0) def structuredTypeExtension(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.StructuredTypeExtensionContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.StructuredTypeExtensionContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_typeExtension - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterTypeExtension" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterTypeExtension"): listener.enterTypeExtension(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitTypeExtension" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitTypeExtension"): listener.exitTypeExtension(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitTypeExtension" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitTypeExtension"): return visitor.visitTypeExtension(self) else: return visitor.visitChildren(self) - - - def typeExtension(self): localctx = OpenSCENARIO2Parser.TypeExtensionContext(self, self._ctx, self.state) @@ -4223,7 +3955,7 @@ def typeExtension(self): try: self.state = 597 self._errHandler.sync(self) - la_ = self._interp.adaptivePredict(self._input,41,self._ctx) + la_ = self._interp.adaptivePredict(self._input, 41, self._ctx) if la_ == 1: self.enterOuterAlt(localctx, 1) self.state = 595 @@ -4236,7 +3968,6 @@ def typeExtension(self): self.structuredTypeExtension() pass - except RecognitionException as re: localctx.exception = re self._errHandler.reportError(self, re) @@ -4245,27 +3976,24 @@ def typeExtension(self): self.exitRule() return localctx - class EnumTypeExtensionContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def enumName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.EnumNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.EnumNameContext, 0) def OPEN_BRACK(self): return self.getToken(OpenSCENARIO2Parser.OPEN_BRACK, 0) - def enumMemberDecl(self, i:int=None): + def enumMemberDecl(self, i: int = None): if i is None: return self.getTypedRuleContexts(OpenSCENARIO2Parser.EnumMemberDeclContext) else: - return self.getTypedRuleContext(OpenSCENARIO2Parser.EnumMemberDeclContext,i) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.EnumMemberDeclContext, i) def CLOSE_BRACK(self): return self.getToken(OpenSCENARIO2Parser.CLOSE_BRACK, 0) @@ -4276,28 +4004,25 @@ def NEWLINE(self): def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_enumTypeExtension - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterEnumTypeExtension" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterEnumTypeExtension"): listener.enterEnumTypeExtension(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitEnumTypeExtension" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitEnumTypeExtension"): listener.exitEnumTypeExtension(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitEnumTypeExtension" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitEnumTypeExtension"): return visitor.visitEnumTypeExtension(self) else: return visitor.visitChildren(self) - - - def enumTypeExtension(self): localctx = OpenSCENARIO2Parser.EnumTypeExtensionContext(self, self._ctx, self.state) self.enterRule(localctx, 90, self.RULE_enumTypeExtension) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 599 @@ -4313,7 +4038,7 @@ def enumTypeExtension(self): self.state = 608 self._errHandler.sync(self) _la = self._input.LA(1) - while _la==OpenSCENARIO2Parser.T__7: + while _la == OpenSCENARIO2Parser.T__7: self.state = 604 self.match(OpenSCENARIO2Parser.T__7) self.state = 605 @@ -4334,17 +4059,15 @@ def enumTypeExtension(self): self.exitRule() return localctx - class StructuredTypeExtensionContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def extendableTypeName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ExtendableTypeNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ExtendableTypeNameContext, 0) def NEWLINE(self): return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) @@ -4355,38 +4078,34 @@ def INDENT(self): def DEDENT(self): return self.getToken(OpenSCENARIO2Parser.DEDENT, 0) - def extensionMemberDecl(self, i:int=None): + def extensionMemberDecl(self, i: int = None): if i is None: return self.getTypedRuleContexts(OpenSCENARIO2Parser.ExtensionMemberDeclContext) else: - return self.getTypedRuleContext(OpenSCENARIO2Parser.ExtensionMemberDeclContext,i) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ExtensionMemberDeclContext, i) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_structuredTypeExtension - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterStructuredTypeExtension" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterStructuredTypeExtension"): listener.enterStructuredTypeExtension(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitStructuredTypeExtension" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitStructuredTypeExtension"): listener.exitStructuredTypeExtension(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitStructuredTypeExtension" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitStructuredTypeExtension"): return visitor.visitStructuredTypeExtension(self) else: return visitor.visitChildren(self) - - - def structuredTypeExtension(self): localctx = OpenSCENARIO2Parser.StructuredTypeExtensionContext(self, self._ctx, self.state) self.enterRule(localctx, 92, self.RULE_structuredTypeExtension) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 614 @@ -4399,13 +4118,13 @@ def structuredTypeExtension(self): self.match(OpenSCENARIO2Parser.NEWLINE) self.state = 618 self.match(OpenSCENARIO2Parser.INDENT) - self.state = 620 + self.state = 620 self._errHandler.sync(self) _la = self._input.LA(1) while True: self.state = 619 self.extensionMemberDecl() - self.state = 622 + self.state = 622 self._errHandler.sync(self) _la = self._input.LA(1) if not ((((_la) & ~0x3f) == 0 and ((1 << _la) & ((1 << OpenSCENARIO2Parser.T__37) | (1 << OpenSCENARIO2Parser.T__45) | (1 << OpenSCENARIO2Parser.T__48) | (1 << OpenSCENARIO2Parser.T__51) | (1 << OpenSCENARIO2Parser.T__52) | (1 << OpenSCENARIO2Parser.T__53))) != 0) or ((((_la - 65)) & ~0x3f) == 0 and ((1 << (_la - 65)) & ((1 << (OpenSCENARIO2Parser.T__64 - 65)) | (1 << (OpenSCENARIO2Parser.T__70 - 65)) | (1 << (OpenSCENARIO2Parser.T__71 - 65)) | (1 << (OpenSCENARIO2Parser.Identifier - 65)))) != 0)): @@ -4421,42 +4140,36 @@ def structuredTypeExtension(self): self.exitRule() return localctx - class ExtendableTypeNameContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def typeName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.TypeNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.TypeNameContext, 0) def qualifiedBehaviorName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.QualifiedBehaviorNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.QualifiedBehaviorNameContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_extendableTypeName - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterExtendableTypeName" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterExtendableTypeName"): listener.enterExtendableTypeName(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitExtendableTypeName" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitExtendableTypeName"): listener.exitExtendableTypeName(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitExtendableTypeName" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitExtendableTypeName"): return visitor.visitExtendableTypeName(self) else: return visitor.visitChildren(self) - - - def extendableTypeName(self): localctx = OpenSCENARIO2Parser.ExtendableTypeNameContext(self, self._ctx, self.state) @@ -4464,7 +4177,7 @@ def extendableTypeName(self): try: self.state = 628 self._errHandler.sync(self) - la_ = self._interp.adaptivePredict(self._input,44,self._ctx) + la_ = self._interp.adaptivePredict(self._input, 44, self._ctx) if la_ == 1: self.enterOuterAlt(localctx, 1) self.state = 626 @@ -4477,7 +4190,6 @@ def extendableTypeName(self): self.qualifiedBehaviorName() pass - except RecognitionException as re: localctx.exception = re self._errHandler.reportError(self, re) @@ -4486,50 +4198,42 @@ def extendableTypeName(self): self.exitRule() return localctx - class ExtensionMemberDeclContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def structMemberDecl(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.StructMemberDeclContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.StructMemberDeclContext, 0) def actorMemberDecl(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ActorMemberDeclContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ActorMemberDeclContext, 0) def scenarioMemberDecl(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ScenarioMemberDeclContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ScenarioMemberDeclContext, 0) def behaviorSpecification(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.BehaviorSpecificationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.BehaviorSpecificationContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_extensionMemberDecl - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterExtensionMemberDecl" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterExtensionMemberDecl"): listener.enterExtensionMemberDecl(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitExtensionMemberDecl" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitExtensionMemberDecl"): listener.exitExtensionMemberDecl(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitExtensionMemberDecl" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitExtensionMemberDecl"): return visitor.visitExtensionMemberDecl(self) else: return visitor.visitChildren(self) - - - def extensionMemberDecl(self): localctx = OpenSCENARIO2Parser.ExtensionMemberDeclContext(self, self._ctx, self.state) @@ -4537,7 +4241,7 @@ def extensionMemberDecl(self): try: self.state = 634 self._errHandler.sync(self) - la_ = self._interp.adaptivePredict(self._input,45,self._ctx) + la_ = self._interp.adaptivePredict(self._input, 45, self._ctx) if la_ == 1: self.enterOuterAlt(localctx, 1) self.state = 630 @@ -4562,7 +4266,6 @@ def extensionMemberDecl(self): self.behaviorSpecification() pass - except RecognitionException as re: localctx.exception = re self._errHandler.reportError(self, re) @@ -4571,61 +4274,53 @@ def extensionMemberDecl(self): self.exitRule() return localctx - class GlobalParameterDeclarationContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser - def fieldName(self, i:int=None): + def fieldName(self, i: int = None): if i is None: return self.getTypedRuleContexts(OpenSCENARIO2Parser.FieldNameContext) else: - return self.getTypedRuleContext(OpenSCENARIO2Parser.FieldNameContext,i) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.FieldNameContext, i) def typeDeclarator(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.TypeDeclaratorContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.TypeDeclaratorContext, 0) def parameterWithDeclaration(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ParameterWithDeclarationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ParameterWithDeclarationContext, 0) def NEWLINE(self): return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) def defaultValue(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.DefaultValueContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.DefaultValueContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_globalParameterDeclaration - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterGlobalParameterDeclaration" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterGlobalParameterDeclaration"): listener.enterGlobalParameterDeclaration(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitGlobalParameterDeclaration" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitGlobalParameterDeclaration"): listener.exitGlobalParameterDeclaration(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitGlobalParameterDeclaration" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitGlobalParameterDeclaration"): return visitor.visitGlobalParameterDeclaration(self) else: return visitor.visitChildren(self) - - - def globalParameterDeclaration(self): localctx = OpenSCENARIO2Parser.GlobalParameterDeclarationContext(self, self._ctx, self.state) self.enterRule(localctx, 98, self.RULE_globalParameterDeclaration) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 636 @@ -4635,7 +4330,7 @@ def globalParameterDeclaration(self): self.state = 642 self._errHandler.sync(self) _la = self._input.LA(1) - while _la==OpenSCENARIO2Parser.T__7: + while _la == OpenSCENARIO2Parser.T__7: self.state = 638 self.match(OpenSCENARIO2Parser.T__7) self.state = 639 @@ -4651,13 +4346,12 @@ def globalParameterDeclaration(self): self.state = 649 self._errHandler.sync(self) _la = self._input.LA(1) - if _la==OpenSCENARIO2Parser.T__20: + if _la == OpenSCENARIO2Parser.T__20: self.state = 647 self.match(OpenSCENARIO2Parser.T__20) self.state = 648 self.defaultValue() - self.state = 653 self._errHandler.sync(self) token = self._input.LA(1) @@ -4680,42 +4374,36 @@ def globalParameterDeclaration(self): self.exitRule() return localctx - class TypeDeclaratorContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def nonAggregateTypeDeclarator(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.NonAggregateTypeDeclaratorContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.NonAggregateTypeDeclaratorContext, 0) def aggregateTypeDeclarator(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.AggregateTypeDeclaratorContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.AggregateTypeDeclaratorContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_typeDeclarator - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterTypeDeclarator" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterTypeDeclarator"): listener.enterTypeDeclarator(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitTypeDeclarator" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitTypeDeclarator"): listener.exitTypeDeclarator(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitTypeDeclarator" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitTypeDeclarator"): return visitor.visitTypeDeclarator(self) else: return visitor.visitChildren(self) - - - def typeDeclarator(self): localctx = OpenSCENARIO2Parser.TypeDeclaratorContext(self, self._ctx, self.state) @@ -4745,46 +4433,39 @@ def typeDeclarator(self): self.exitRule() return localctx - class NonAggregateTypeDeclaratorContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def primitiveType(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.PrimitiveTypeContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.PrimitiveTypeContext, 0) def typeName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.TypeNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.TypeNameContext, 0) def qualifiedBehaviorName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.QualifiedBehaviorNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.QualifiedBehaviorNameContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_nonAggregateTypeDeclarator - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterNonAggregateTypeDeclarator" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterNonAggregateTypeDeclarator"): listener.enterNonAggregateTypeDeclarator(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitNonAggregateTypeDeclarator" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitNonAggregateTypeDeclarator"): listener.exitNonAggregateTypeDeclarator(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitNonAggregateTypeDeclarator" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitNonAggregateTypeDeclarator"): return visitor.visitNonAggregateTypeDeclarator(self) else: return visitor.visitChildren(self) - - - def nonAggregateTypeDeclarator(self): localctx = OpenSCENARIO2Parser.NonAggregateTypeDeclaratorContext(self, self._ctx, self.state) @@ -4792,7 +4473,7 @@ def nonAggregateTypeDeclarator(self): try: self.state = 662 self._errHandler.sync(self) - la_ = self._interp.adaptivePredict(self._input,50,self._ctx) + la_ = self._interp.adaptivePredict(self._input, 50, self._ctx) if la_ == 1: self.enterOuterAlt(localctx, 1) self.state = 659 @@ -4811,7 +4492,6 @@ def nonAggregateTypeDeclarator(self): self.qualifiedBehaviorName() pass - except RecognitionException as re: localctx.exception = re self._errHandler.reportError(self, re) @@ -4820,38 +4500,33 @@ def nonAggregateTypeDeclarator(self): self.exitRule() return localctx - class AggregateTypeDeclaratorContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def listTypeDeclarator(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ListTypeDeclaratorContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ListTypeDeclaratorContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_aggregateTypeDeclarator - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterAggregateTypeDeclarator" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterAggregateTypeDeclarator"): listener.enterAggregateTypeDeclarator(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitAggregateTypeDeclarator" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitAggregateTypeDeclarator"): listener.exitAggregateTypeDeclarator(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitAggregateTypeDeclarator" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitAggregateTypeDeclarator"): return visitor.visitAggregateTypeDeclarator(self) else: return visitor.visitChildren(self) - - - def aggregateTypeDeclarator(self): localctx = OpenSCENARIO2Parser.AggregateTypeDeclaratorContext(self, self._ctx, self.state) @@ -4868,38 +4543,33 @@ def aggregateTypeDeclarator(self): self.exitRule() return localctx - class ListTypeDeclaratorContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def nonAggregateTypeDeclarator(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.NonAggregateTypeDeclaratorContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.NonAggregateTypeDeclaratorContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_listTypeDeclarator - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterListTypeDeclarator" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterListTypeDeclarator"): listener.enterListTypeDeclarator(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitListTypeDeclarator" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitListTypeDeclarator"): listener.exitListTypeDeclarator(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitListTypeDeclarator" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitListTypeDeclarator"): return visitor.visitListTypeDeclarator(self) else: return visitor.visitChildren(self) - - - def listTypeDeclarator(self): localctx = OpenSCENARIO2Parser.ListTypeDeclaratorContext(self, self._ctx, self.state) @@ -4920,40 +4590,35 @@ def listTypeDeclarator(self): self.exitRule() return localctx - class PrimitiveTypeContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser - def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_primitiveType - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterPrimitiveType" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterPrimitiveType"): listener.enterPrimitiveType(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitPrimitiveType" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitPrimitiveType"): listener.exitPrimitiveType(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitPrimitiveType" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitPrimitiveType"): return visitor.visitPrimitiveType(self) else: return visitor.visitChildren(self) - - - def primitiveType(self): localctx = OpenSCENARIO2Parser.PrimitiveTypeContext(self, self._ctx, self.state) self.enterRule(localctx, 108, self.RULE_primitiveType) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 670 @@ -4971,11 +4636,10 @@ def primitiveType(self): self.exitRule() return localctx - class TypeNameContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser @@ -4985,23 +4649,20 @@ def Identifier(self): def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_typeName - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterTypeName" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterTypeName"): listener.enterTypeName(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitTypeName" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitTypeName"): listener.exitTypeName(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitTypeName" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitTypeName"): return visitor.visitTypeName(self) else: return visitor.visitChildren(self) - - - def typeName(self): localctx = OpenSCENARIO2Parser.TypeNameContext(self, self._ctx, self.state) @@ -5018,17 +4679,15 @@ def typeName(self): self.exitRule() return localctx - class EventDeclarationContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def eventName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.EventNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.EventNameContext, 0) def NEWLINE(self): return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) @@ -5037,41 +4696,36 @@ def OPEN_PAREN(self): return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) def argumentListSpecification(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ArgumentListSpecificationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ArgumentListSpecificationContext, 0) def CLOSE_PAREN(self): return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) def eventSpecification(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.EventSpecificationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.EventSpecificationContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_eventDeclaration - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterEventDeclaration" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterEventDeclaration"): listener.enterEventDeclaration(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitEventDeclaration" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitEventDeclaration"): listener.exitEventDeclaration(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitEventDeclaration" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitEventDeclaration"): return visitor.visitEventDeclaration(self) else: return visitor.visitChildren(self) - - - def eventDeclaration(self): localctx = OpenSCENARIO2Parser.EventDeclarationContext(self, self._ctx, self.state) self.enterRule(localctx, 112, self.RULE_eventDeclaration) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 674 @@ -5081,7 +4735,7 @@ def eventDeclaration(self): self.state = 680 self._errHandler.sync(self) _la = self._input.LA(1) - if _la==OpenSCENARIO2Parser.OPEN_PAREN: + if _la == OpenSCENARIO2Parser.OPEN_PAREN: self.state = 676 self.match(OpenSCENARIO2Parser.OPEN_PAREN) self.state = 677 @@ -5089,17 +4743,15 @@ def eventDeclaration(self): self.state = 678 self.match(OpenSCENARIO2Parser.CLOSE_PAREN) - self.state = 684 self._errHandler.sync(self) _la = self._input.LA(1) - if _la==OpenSCENARIO2Parser.T__3: + if _la == OpenSCENARIO2Parser.T__3: self.state = 682 self.match(OpenSCENARIO2Parser.T__3) self.state = 683 self.eventSpecification() - self.state = 686 self.match(OpenSCENARIO2Parser.NEWLINE) except RecognitionException as re: @@ -5110,51 +4762,44 @@ def eventDeclaration(self): self.exitRule() return localctx - class EventSpecificationContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def eventReference(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.EventReferenceContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.EventReferenceContext, 0) def eventCondition(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.EventConditionContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.EventConditionContext, 0) def eventFieldDecl(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.EventFieldDeclContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.EventFieldDeclContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_eventSpecification - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterEventSpecification" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterEventSpecification"): listener.enterEventSpecification(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitEventSpecification" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitEventSpecification"): listener.exitEventSpecification(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitEventSpecification" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitEventSpecification"): return visitor.visitEventSpecification(self) else: return visitor.visitChildren(self) - - - def eventSpecification(self): localctx = OpenSCENARIO2Parser.EventSpecificationContext(self, self._ctx, self.state) self.enterRule(localctx, 114, self.RULE_eventSpecification) - self._la = 0 # Token type + self._la = 0 # Token type try: self.state = 697 self._errHandler.sync(self) @@ -5166,21 +4811,19 @@ def eventSpecification(self): self.state = 694 self._errHandler.sync(self) _la = self._input.LA(1) - if _la==OpenSCENARIO2Parser.T__38 or _la==OpenSCENARIO2Parser.T__40: + if _la == OpenSCENARIO2Parser.T__38 or _la == OpenSCENARIO2Parser.T__40: self.state = 690 self._errHandler.sync(self) _la = self._input.LA(1) - if _la==OpenSCENARIO2Parser.T__40: + if _la == OpenSCENARIO2Parser.T__40: self.state = 689 self.eventFieldDecl() - self.state = 692 self.match(OpenSCENARIO2Parser.T__38) self.state = 693 self.eventCondition() - pass elif token in [OpenSCENARIO2Parser.T__41, OpenSCENARIO2Parser.T__42, OpenSCENARIO2Parser.T__43, OpenSCENARIO2Parser.T__44, OpenSCENARIO2Parser.T__72, OpenSCENARIO2Parser.T__77, OpenSCENARIO2Parser.T__85, OpenSCENARIO2Parser.T__89, OpenSCENARIO2Parser.OPEN_BRACK, OpenSCENARIO2Parser.OPEN_PAREN, OpenSCENARIO2Parser.StringLiteral, OpenSCENARIO2Parser.FloatLiteral, OpenSCENARIO2Parser.UintLiteral, OpenSCENARIO2Parser.HexUintLiteral, OpenSCENARIO2Parser.IntLiteral, OpenSCENARIO2Parser.BoolLiteral, OpenSCENARIO2Parser.Identifier]: self.enterOuterAlt(localctx, 2) @@ -5198,38 +4841,33 @@ def eventSpecification(self): self.exitRule() return localctx - class EventReferenceContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def eventPath(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.EventPathContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.EventPathContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_eventReference - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterEventReference" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterEventReference"): listener.enterEventReference(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitEventReference" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitEventReference"): listener.exitEventReference(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitEventReference" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitEventReference"): return visitor.visitEventReference(self) else: return visitor.visitChildren(self) - - - def eventReference(self): localctx = OpenSCENARIO2Parser.EventReferenceContext(self, self._ctx, self.state) @@ -5248,38 +4886,33 @@ def eventReference(self): self.exitRule() return localctx - class EventFieldDeclContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def eventFieldName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.EventFieldNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.EventFieldNameContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_eventFieldDecl - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterEventFieldDecl" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterEventFieldDecl"): listener.enterEventFieldDecl(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitEventFieldDecl" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitEventFieldDecl"): listener.exitEventFieldDecl(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitEventFieldDecl" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitEventFieldDecl"): return visitor.visitEventFieldDecl(self) else: return visitor.visitChildren(self) - - - def eventFieldDecl(self): localctx = OpenSCENARIO2Parser.EventFieldDeclContext(self, self._ctx, self.state) @@ -5298,11 +4931,10 @@ def eventFieldDecl(self): self.exitRule() return localctx - class EventFieldNameContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser @@ -5312,23 +4944,20 @@ def Identifier(self): def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_eventFieldName - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterEventFieldName" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterEventFieldName"): listener.enterEventFieldName(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitEventFieldName" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitEventFieldName"): listener.exitEventFieldName(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitEventFieldName" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitEventFieldName"): return visitor.visitEventFieldName(self) else: return visitor.visitChildren(self) - - - def eventFieldName(self): localctx = OpenSCENARIO2Parser.EventFieldNameContext(self, self._ctx, self.state) @@ -5345,11 +4974,10 @@ def eventFieldName(self): self.exitRule() return localctx - class EventNameContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser @@ -5359,23 +4987,20 @@ def Identifier(self): def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_eventName - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterEventName" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterEventName"): listener.enterEventName(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitEventName" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitEventName"): listener.exitEventName(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitEventName" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitEventName"): return visitor.visitEventName(self) else: return visitor.visitChildren(self) - - - def eventName(self): localctx = OpenSCENARIO2Parser.EventNameContext(self, self._ctx, self.state) @@ -5392,42 +5017,36 @@ def eventName(self): self.exitRule() return localctx - class EventPathContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def eventName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.EventNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.EventNameContext, 0) def expression(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_eventPath - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterEventPath" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterEventPath"): listener.enterEventPath(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitEventPath" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitEventPath"): listener.exitEventPath(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitEventPath" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitEventPath"): return visitor.visitEventPath(self) else: return visitor.visitChildren(self) - - - def eventPath(self): localctx = OpenSCENARIO2Parser.EventPathContext(self, self._ctx, self.state) @@ -5436,14 +5055,13 @@ def eventPath(self): self.enterOuterAlt(localctx, 1) self.state = 712 self._errHandler.sync(self) - la_ = self._interp.adaptivePredict(self._input,56,self._ctx) + la_ = self._interp.adaptivePredict(self._input, 56, self._ctx) if la_ == 1: self.state = 709 self.expression() self.state = 710 self.match(OpenSCENARIO2Parser.T__1) - self.state = 714 self.eventName() except RecognitionException as re: @@ -5454,54 +5072,45 @@ def eventPath(self): self.exitRule() return localctx - class EventConditionContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def boolExpression(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.BoolExpressionContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.BoolExpressionContext, 0) def riseExpression(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.RiseExpressionContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.RiseExpressionContext, 0) def fallExpression(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.FallExpressionContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.FallExpressionContext, 0) def elapsedExpression(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ElapsedExpressionContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ElapsedExpressionContext, 0) def everyExpression(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.EveryExpressionContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.EveryExpressionContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_eventCondition - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterEventCondition" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterEventCondition"): listener.enterEventCondition(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitEventCondition" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitEventCondition"): listener.exitEventCondition(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitEventCondition" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitEventCondition"): return visitor.visitEventCondition(self) else: return visitor.visitChildren(self) - - - def eventCondition(self): localctx = OpenSCENARIO2Parser.EventConditionContext(self, self._ctx, self.state) @@ -5546,11 +5155,10 @@ def eventCondition(self): self.exitRule() return localctx - class RiseExpressionContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser @@ -5558,8 +5166,7 @@ def OPEN_PAREN(self): return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) def boolExpression(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.BoolExpressionContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.BoolExpressionContext, 0) def CLOSE_PAREN(self): return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) @@ -5567,23 +5174,20 @@ def CLOSE_PAREN(self): def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_riseExpression - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterRiseExpression" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterRiseExpression"): listener.enterRiseExpression(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitRiseExpression" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitRiseExpression"): listener.exitRiseExpression(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitRiseExpression" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitRiseExpression"): return visitor.visitRiseExpression(self) else: return visitor.visitChildren(self) - - - def riseExpression(self): localctx = OpenSCENARIO2Parser.RiseExpressionContext(self, self._ctx, self.state) @@ -5606,11 +5210,10 @@ def riseExpression(self): self.exitRule() return localctx - class FallExpressionContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser @@ -5618,8 +5221,7 @@ def OPEN_PAREN(self): return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) def boolExpression(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.BoolExpressionContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.BoolExpressionContext, 0) def CLOSE_PAREN(self): return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) @@ -5627,23 +5229,20 @@ def CLOSE_PAREN(self): def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_fallExpression - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterFallExpression" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterFallExpression"): listener.enterFallExpression(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitFallExpression" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitFallExpression"): listener.exitFallExpression(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitFallExpression" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitFallExpression"): return visitor.visitFallExpression(self) else: return visitor.visitChildren(self) - - - def fallExpression(self): localctx = OpenSCENARIO2Parser.FallExpressionContext(self, self._ctx, self.state) @@ -5666,11 +5265,10 @@ def fallExpression(self): self.exitRule() return localctx - class ElapsedExpressionContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser @@ -5678,8 +5276,7 @@ def OPEN_PAREN(self): return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) def durationExpression(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.DurationExpressionContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.DurationExpressionContext, 0) def CLOSE_PAREN(self): return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) @@ -5687,23 +5284,20 @@ def CLOSE_PAREN(self): def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_elapsedExpression - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterElapsedExpression" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterElapsedExpression"): listener.enterElapsedExpression(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitElapsedExpression" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitElapsedExpression"): listener.exitElapsedExpression(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitElapsedExpression" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitElapsedExpression"): return visitor.visitElapsedExpression(self) else: return visitor.visitChildren(self) - - - def elapsedExpression(self): localctx = OpenSCENARIO2Parser.ElapsedExpressionContext(self, self._ctx, self.state) @@ -5726,24 +5320,22 @@ def elapsedExpression(self): self.exitRule() return localctx - class EveryExpressionContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser - self._Identifier = None # Token + self._Identifier = None # Token def OPEN_PAREN(self): return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) - def durationExpression(self, i:int=None): + def durationExpression(self, i: int = None): if i is None: return self.getTypedRuleContexts(OpenSCENARIO2Parser.DurationExpressionContext) else: - return self.getTypedRuleContext(OpenSCENARIO2Parser.DurationExpressionContext,i) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.DurationExpressionContext, i) def CLOSE_PAREN(self): return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) @@ -5754,28 +5346,25 @@ def Identifier(self): def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_everyExpression - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterEveryExpression" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterEveryExpression"): listener.enterEveryExpression(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitEveryExpression" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitEveryExpression"): listener.exitEveryExpression(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitEveryExpression" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitEveryExpression"): return visitor.visitEveryExpression(self) else: return visitor.visitChildren(self) - - - def everyExpression(self): localctx = OpenSCENARIO2Parser.EveryExpressionContext(self, self._ctx, self.state) self.enterRule(localctx, 134, self.RULE_everyExpression) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 738 @@ -5787,15 +5376,15 @@ def everyExpression(self): self.state = 746 self._errHandler.sync(self) _la = self._input.LA(1) - if _la==OpenSCENARIO2Parser.T__7: + if _la == OpenSCENARIO2Parser.T__7: self.state = 741 self.match(OpenSCENARIO2Parser.T__7) self.state = 742 localctx._Identifier = self.match(OpenSCENARIO2Parser.Identifier) - + offsetName = (None if localctx._Identifier is None else localctx._Identifier.text) - if( not (offsetName == "offset") ): - print("%s must be offset" %offsetName) + if(not (offsetName == "offset")): + print("%s must be offset" % offsetName) raise NoViableAltException(self) self.state = 744 @@ -5803,7 +5392,6 @@ def everyExpression(self): self.state = 745 self.durationExpression() - self.state = 748 self.match(OpenSCENARIO2Parser.CLOSE_PAREN) except RecognitionException as re: @@ -5814,38 +5402,33 @@ def everyExpression(self): self.exitRule() return localctx - class BoolExpressionContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def expression(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_boolExpression - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterBoolExpression" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterBoolExpression"): listener.enterBoolExpression(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitBoolExpression" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitBoolExpression"): listener.exitBoolExpression(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitBoolExpression" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitBoolExpression"): return visitor.visitBoolExpression(self) else: return visitor.visitChildren(self) - - - def boolExpression(self): localctx = OpenSCENARIO2Parser.BoolExpressionContext(self, self._ctx, self.state) @@ -5862,38 +5445,33 @@ def boolExpression(self): self.exitRule() return localctx - class DurationExpressionContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def expression(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_durationExpression - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterDurationExpression" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterDurationExpression"): listener.enterDurationExpression(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitDurationExpression" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitDurationExpression"): listener.exitDurationExpression(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitDurationExpression" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitDurationExpression"): return visitor.visitDurationExpression(self) else: return visitor.visitChildren(self) - - - def durationExpression(self): localctx = OpenSCENARIO2Parser.DurationExpressionContext(self, self._ctx, self.state) @@ -5910,42 +5488,36 @@ def durationExpression(self): self.exitRule() return localctx - class FieldDeclarationContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def parameterDeclaration(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ParameterDeclarationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ParameterDeclarationContext, 0) def variableDeclaration(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.VariableDeclarationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.VariableDeclarationContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_fieldDeclaration - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterFieldDeclaration" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterFieldDeclaration"): listener.enterFieldDeclaration(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitFieldDeclaration" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitFieldDeclaration"): listener.exitFieldDeclaration(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitFieldDeclaration" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitFieldDeclaration"): return visitor.visitFieldDeclaration(self) else: return visitor.visitChildren(self) - - - def fieldDeclaration(self): localctx = OpenSCENARIO2Parser.FieldDeclarationContext(self, self._ctx, self.state) @@ -5975,61 +5547,53 @@ def fieldDeclaration(self): self.exitRule() return localctx - class ParameterDeclarationContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser - def fieldName(self, i:int=None): + def fieldName(self, i: int = None): if i is None: return self.getTypedRuleContexts(OpenSCENARIO2Parser.FieldNameContext) else: - return self.getTypedRuleContext(OpenSCENARIO2Parser.FieldNameContext,i) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.FieldNameContext, i) def typeDeclarator(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.TypeDeclaratorContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.TypeDeclaratorContext, 0) def parameterWithDeclaration(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ParameterWithDeclarationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ParameterWithDeclarationContext, 0) def NEWLINE(self): return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) def defaultValue(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.DefaultValueContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.DefaultValueContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_parameterDeclaration - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterParameterDeclaration" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterParameterDeclaration"): listener.enterParameterDeclaration(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitParameterDeclaration" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitParameterDeclaration"): listener.exitParameterDeclaration(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitParameterDeclaration" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitParameterDeclaration"): return visitor.visitParameterDeclaration(self) else: return visitor.visitChildren(self) - - - def parameterDeclaration(self): localctx = OpenSCENARIO2Parser.ParameterDeclarationContext(self, self._ctx, self.state) self.enterRule(localctx, 142, self.RULE_parameterDeclaration) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 758 @@ -6037,7 +5601,7 @@ def parameterDeclaration(self): self.state = 763 self._errHandler.sync(self) _la = self._input.LA(1) - while _la==OpenSCENARIO2Parser.T__7: + while _la == OpenSCENARIO2Parser.T__7: self.state = 759 self.match(OpenSCENARIO2Parser.T__7) self.state = 760 @@ -6053,13 +5617,12 @@ def parameterDeclaration(self): self.state = 770 self._errHandler.sync(self) _la = self._input.LA(1) - if _la==OpenSCENARIO2Parser.T__20: + if _la == OpenSCENARIO2Parser.T__20: self.state = 768 self.match(OpenSCENARIO2Parser.T__20) self.state = 769 self.defaultValue() - self.state = 774 self._errHandler.sync(self) token = self._input.LA(1) @@ -6082,61 +5645,53 @@ def parameterDeclaration(self): self.exitRule() return localctx - class VariableDeclarationContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser - def fieldName(self, i:int=None): + def fieldName(self, i: int = None): if i is None: return self.getTypedRuleContexts(OpenSCENARIO2Parser.FieldNameContext) else: - return self.getTypedRuleContext(OpenSCENARIO2Parser.FieldNameContext,i) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.FieldNameContext, i) def typeDeclarator(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.TypeDeclaratorContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.TypeDeclaratorContext, 0) def NEWLINE(self): return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) def sampleExpression(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.SampleExpressionContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.SampleExpressionContext, 0) def valueExp(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ValueExpContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ValueExpContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_variableDeclaration - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterVariableDeclaration" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterVariableDeclaration"): listener.enterVariableDeclaration(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitVariableDeclaration" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitVariableDeclaration"): listener.exitVariableDeclaration(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitVariableDeclaration" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitVariableDeclaration"): return visitor.visitVariableDeclaration(self) else: return visitor.visitChildren(self) - - - def variableDeclaration(self): localctx = OpenSCENARIO2Parser.VariableDeclarationContext(self, self._ctx, self.state) self.enterRule(localctx, 144, self.RULE_variableDeclaration) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 776 @@ -6146,7 +5701,7 @@ def variableDeclaration(self): self.state = 782 self._errHandler.sync(self) _la = self._input.LA(1) - while _la==OpenSCENARIO2Parser.T__7: + while _la == OpenSCENARIO2Parser.T__7: self.state = 778 self.match(OpenSCENARIO2Parser.T__7) self.state = 779 @@ -6162,7 +5717,7 @@ def variableDeclaration(self): self.state = 792 self._errHandler.sync(self) _la = self._input.LA(1) - if _la==OpenSCENARIO2Parser.T__20: + if _la == OpenSCENARIO2Parser.T__20: self.state = 787 self.match(OpenSCENARIO2Parser.T__20) self.state = 790 @@ -6179,8 +5734,6 @@ def variableDeclaration(self): else: raise NoViableAltException(self) - - self.state = 794 self.match(OpenSCENARIO2Parser.NEWLINE) except RecognitionException as re: @@ -6191,11 +5744,10 @@ def variableDeclaration(self): self.exitRule() return localctx - class SampleExpressionContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser @@ -6203,45 +5755,39 @@ def OPEN_PAREN(self): return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) def expression(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext, 0) def eventSpecification(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.EventSpecificationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.EventSpecificationContext, 0) def CLOSE_PAREN(self): return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) def defaultValue(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.DefaultValueContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.DefaultValueContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_sampleExpression - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterSampleExpression" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterSampleExpression"): listener.enterSampleExpression(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitSampleExpression" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitSampleExpression"): listener.exitSampleExpression(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitSampleExpression" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitSampleExpression"): return visitor.visitSampleExpression(self) else: return visitor.visitChildren(self) - - - def sampleExpression(self): localctx = OpenSCENARIO2Parser.SampleExpressionContext(self, self._ctx, self.state) self.enterRule(localctx, 146, self.RULE_sampleExpression) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 796 @@ -6257,13 +5803,12 @@ def sampleExpression(self): self.state = 803 self._errHandler.sync(self) _la = self._input.LA(1) - if _la==OpenSCENARIO2Parser.T__7: + if _la == OpenSCENARIO2Parser.T__7: self.state = 801 self.match(OpenSCENARIO2Parser.T__7) self.state = 802 self.defaultValue() - self.state = 805 self.match(OpenSCENARIO2Parser.CLOSE_PAREN) except RecognitionException as re: @@ -6274,38 +5819,33 @@ def sampleExpression(self): self.exitRule() return localctx - class DefaultValueContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def expression(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_defaultValue - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterDefaultValue" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterDefaultValue"): listener.enterDefaultValue(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitDefaultValue" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitDefaultValue"): listener.exitDefaultValue(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitDefaultValue" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitDefaultValue"): return visitor.visitDefaultValue(self) else: return visitor.visitChildren(self) - - - def defaultValue(self): localctx = OpenSCENARIO2Parser.DefaultValueContext(self, self._ctx, self.state) @@ -6322,11 +5862,10 @@ def defaultValue(self): self.exitRule() return localctx - class ParameterWithDeclarationContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser @@ -6339,38 +5878,34 @@ def INDENT(self): def DEDENT(self): return self.getToken(OpenSCENARIO2Parser.DEDENT, 0) - def parameterWithMember(self, i:int=None): + def parameterWithMember(self, i: int = None): if i is None: return self.getTypedRuleContexts(OpenSCENARIO2Parser.ParameterWithMemberContext) else: - return self.getTypedRuleContext(OpenSCENARIO2Parser.ParameterWithMemberContext,i) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ParameterWithMemberContext, i) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_parameterWithDeclaration - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterParameterWithDeclaration" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterParameterWithDeclaration"): listener.enterParameterWithDeclaration(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitParameterWithDeclaration" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitParameterWithDeclaration"): listener.exitParameterWithDeclaration(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitParameterWithDeclaration" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitParameterWithDeclaration"): return visitor.visitParameterWithDeclaration(self) else: return visitor.visitChildren(self) - - - def parameterWithDeclaration(self): localctx = OpenSCENARIO2Parser.ParameterWithDeclarationContext(self, self._ctx, self.state) self.enterRule(localctx, 150, self.RULE_parameterWithDeclaration) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 809 @@ -6381,13 +5916,13 @@ def parameterWithDeclaration(self): self.match(OpenSCENARIO2Parser.NEWLINE) self.state = 812 self.match(OpenSCENARIO2Parser.INDENT) - self.state = 814 + self.state = 814 self._errHandler.sync(self) _la = self._input.LA(1) while True: self.state = 813 self.parameterWithMember() - self.state = 816 + self.state = 816 self._errHandler.sync(self) _la = self._input.LA(1) if not (((((_la - 49)) & ~0x3f) == 0 and ((1 << (_la - 49)) & ((1 << (OpenSCENARIO2Parser.T__48 - 49)) | (1 << (OpenSCENARIO2Parser.T__51 - 49)) | (1 << (OpenSCENARIO2Parser.T__70 - 49)) | (1 << (OpenSCENARIO2Parser.T__71 - 49)))) != 0)): @@ -6403,42 +5938,36 @@ def parameterWithDeclaration(self): self.exitRule() return localctx - class ParameterWithMemberContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def constraintDeclaration(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ConstraintDeclarationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ConstraintDeclarationContext, 0) def coverageDeclaration(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.CoverageDeclarationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.CoverageDeclarationContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_parameterWithMember - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterParameterWithMember" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterParameterWithMember"): listener.enterParameterWithMember(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitParameterWithMember" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitParameterWithMember"): listener.exitParameterWithMember(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitParameterWithMember" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitParameterWithMember"): return visitor.visitParameterWithMember(self) else: return visitor.visitChildren(self) - - - def parameterWithMember(self): localctx = OpenSCENARIO2Parser.ParameterWithMemberContext(self, self._ctx, self.state) @@ -6468,42 +5997,36 @@ def parameterWithMember(self): self.exitRule() return localctx - class ConstraintDeclarationContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def keepConstraintDeclaration(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.KeepConstraintDeclarationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.KeepConstraintDeclarationContext, 0) def removeDefaultDeclaration(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.RemoveDefaultDeclarationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.RemoveDefaultDeclarationContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_constraintDeclaration - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterConstraintDeclaration" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterConstraintDeclaration"): listener.enterConstraintDeclaration(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitConstraintDeclaration" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitConstraintDeclaration"): listener.exitConstraintDeclaration(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitConstraintDeclaration" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitConstraintDeclaration"): return visitor.visitConstraintDeclaration(self) else: return visitor.visitChildren(self) - - - def constraintDeclaration(self): localctx = OpenSCENARIO2Parser.ConstraintDeclarationContext(self, self._ctx, self.state) @@ -6533,11 +6056,10 @@ def constraintDeclaration(self): self.exitRule() return localctx - class KeepConstraintDeclarationContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser @@ -6545,8 +6067,7 @@ def OPEN_PAREN(self): return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) def constraintExpression(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ConstraintExpressionContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ConstraintExpressionContext, 0) def CLOSE_PAREN(self): return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) @@ -6555,34 +6076,30 @@ def NEWLINE(self): return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) def constraintQualifier(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ConstraintQualifierContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ConstraintQualifierContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_keepConstraintDeclaration - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterKeepConstraintDeclaration" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterKeepConstraintDeclaration"): listener.enterKeepConstraintDeclaration(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitKeepConstraintDeclaration" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitKeepConstraintDeclaration"): listener.exitKeepConstraintDeclaration(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitKeepConstraintDeclaration" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitKeepConstraintDeclaration"): return visitor.visitKeepConstraintDeclaration(self) else: return visitor.visitChildren(self) - - - def keepConstraintDeclaration(self): localctx = OpenSCENARIO2Parser.KeepConstraintDeclarationContext(self, self._ctx, self.state) self.enterRule(localctx, 156, self.RULE_keepConstraintDeclaration) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 828 @@ -6592,11 +6109,10 @@ def keepConstraintDeclaration(self): self.state = 831 self._errHandler.sync(self) _la = self._input.LA(1) - if _la==OpenSCENARIO2Parser.T__49 or _la==OpenSCENARIO2Parser.T__50: + if _la == OpenSCENARIO2Parser.T__49 or _la == OpenSCENARIO2Parser.T__50: self.state = 830 self.constraintQualifier() - self.state = 833 self.constraintExpression() self.state = 834 @@ -6611,45 +6127,40 @@ def keepConstraintDeclaration(self): self.exitRule() return localctx - class ConstraintQualifierContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser - def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_constraintQualifier - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterConstraintQualifier" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterConstraintQualifier"): listener.enterConstraintQualifier(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitConstraintQualifier" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitConstraintQualifier"): listener.exitConstraintQualifier(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitConstraintQualifier" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitConstraintQualifier"): return visitor.visitConstraintQualifier(self) else: return visitor.visitChildren(self) - - - def constraintQualifier(self): localctx = OpenSCENARIO2Parser.ConstraintQualifierContext(self, self._ctx, self.state) self.enterRule(localctx, 158, self.RULE_constraintQualifier) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 837 _la = self._input.LA(1) - if not(_la==OpenSCENARIO2Parser.T__49 or _la==OpenSCENARIO2Parser.T__50): + if not(_la == OpenSCENARIO2Parser.T__49 or _la == OpenSCENARIO2Parser.T__50): self._errHandler.recoverInline(self) else: self._errHandler.reportMatch(self) @@ -6662,38 +6173,33 @@ def constraintQualifier(self): self.exitRule() return localctx - class ConstraintExpressionContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def expression(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_constraintExpression - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterConstraintExpression" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterConstraintExpression"): listener.enterConstraintExpression(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitConstraintExpression" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitConstraintExpression"): listener.exitConstraintExpression(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitConstraintExpression" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitConstraintExpression"): return visitor.visitConstraintExpression(self) else: return visitor.visitChildren(self) - - - def constraintExpression(self): localctx = OpenSCENARIO2Parser.ConstraintExpressionContext(self, self._ctx, self.state) @@ -6710,11 +6216,10 @@ def constraintExpression(self): self.exitRule() return localctx - class RemoveDefaultDeclarationContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser @@ -6722,8 +6227,7 @@ def OPEN_PAREN(self): return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) def parameterReference(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ParameterReferenceContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ParameterReferenceContext, 0) def CLOSE_PAREN(self): return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) @@ -6734,23 +6238,20 @@ def NEWLINE(self): def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_removeDefaultDeclaration - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterRemoveDefaultDeclaration" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterRemoveDefaultDeclaration"): listener.enterRemoveDefaultDeclaration(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitRemoveDefaultDeclaration" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitRemoveDefaultDeclaration"): listener.exitRemoveDefaultDeclaration(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitRemoveDefaultDeclaration" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitRemoveDefaultDeclaration"): return visitor.visitRemoveDefaultDeclaration(self) else: return visitor.visitChildren(self) - - - def removeDefaultDeclaration(self): localctx = OpenSCENARIO2Parser.RemoveDefaultDeclarationContext(self, self._ctx, self.state) @@ -6775,42 +6276,36 @@ def removeDefaultDeclaration(self): self.exitRule() return localctx - class ParameterReferenceContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def fieldName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.FieldNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.FieldNameContext, 0) def fieldAccess(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.FieldAccessContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.FieldAccessContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_parameterReference - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterParameterReference" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterParameterReference"): listener.enterParameterReference(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitParameterReference" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitParameterReference"): listener.exitParameterReference(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitParameterReference" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitParameterReference"): return visitor.visitParameterReference(self) else: return visitor.visitChildren(self) - - - def parameterReference(self): localctx = OpenSCENARIO2Parser.ParameterReferenceContext(self, self._ctx, self.state) @@ -6818,7 +6313,7 @@ def parameterReference(self): try: self.state = 849 self._errHandler.sync(self) - la_ = self._interp.adaptivePredict(self._input,71,self._ctx) + la_ = self._interp.adaptivePredict(self._input, 71, self._ctx) if la_ == 1: self.enterOuterAlt(localctx, 1) self.state = 847 @@ -6831,7 +6326,6 @@ def parameterReference(self): self.fieldAccess() pass - except RecognitionException as re: localctx.exception = re self._errHandler.reportError(self, re) @@ -6840,17 +6334,15 @@ def parameterReference(self): self.exitRule() return localctx - class ModifierInvocationContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def modifierName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ModifierNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ModifierNameContext, 0) def OPEN_PAREN(self): return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) @@ -6862,51 +6354,45 @@ def NEWLINE(self): return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) def argumentList(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ArgumentListContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ArgumentListContext, 0) def behaviorExpression(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.BehaviorExpressionContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.BehaviorExpressionContext, 0) def actorExpression(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ActorExpressionContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ActorExpressionContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_modifierInvocation - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterModifierInvocation" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterModifierInvocation"): listener.enterModifierInvocation(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitModifierInvocation" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitModifierInvocation"): listener.exitModifierInvocation(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitModifierInvocation" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitModifierInvocation"): return visitor.visitModifierInvocation(self) else: return visitor.visitChildren(self) - - - def modifierInvocation(self): localctx = OpenSCENARIO2Parser.ModifierInvocationContext(self, self._ctx, self.state) self.enterRule(localctx, 166, self.RULE_modifierInvocation) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 857 self._errHandler.sync(self) - la_ = self._interp.adaptivePredict(self._input,73,self._ctx) + la_ = self._interp.adaptivePredict(self._input, 73, self._ctx) if la_ == 1: self.state = 853 self._errHandler.sync(self) - la_ = self._interp.adaptivePredict(self._input,72,self._ctx) + la_ = self._interp.adaptivePredict(self._input, 72, self._ctx) if la_ == 1: self.state = 851 self.behaviorExpression() @@ -6917,11 +6403,9 @@ def modifierInvocation(self): self.actorExpression() pass - self.state = 855 self.match(OpenSCENARIO2Parser.T__1) - self.state = 859 self.modifierName() self.state = 860 @@ -6933,7 +6417,6 @@ def modifierInvocation(self): self.state = 861 self.argumentList() - self.state = 864 self.match(OpenSCENARIO2Parser.CLOSE_PAREN) self.state = 865 @@ -6946,42 +6429,36 @@ def modifierInvocation(self): self.exitRule() return localctx - class BehaviorExpressionContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def behaviorName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.BehaviorNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.BehaviorNameContext, 0) def actorExpression(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ActorExpressionContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ActorExpressionContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_behaviorExpression - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterBehaviorExpression" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterBehaviorExpression"): listener.enterBehaviorExpression(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitBehaviorExpression" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitBehaviorExpression"): listener.exitBehaviorExpression(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitBehaviorExpression" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitBehaviorExpression"): return visitor.visitBehaviorExpression(self) else: return visitor.visitChildren(self) - - - def behaviorExpression(self): localctx = OpenSCENARIO2Parser.BehaviorExpressionContext(self, self._ctx, self.state) @@ -7002,42 +6479,36 @@ def behaviorExpression(self): self.exitRule() return localctx - class BehaviorSpecificationContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def onDirective(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.OnDirectiveContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.OnDirectiveContext, 0) def doDirective(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.DoDirectiveContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.DoDirectiveContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_behaviorSpecification - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterBehaviorSpecification" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterBehaviorSpecification"): listener.enterBehaviorSpecification(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitBehaviorSpecification" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitBehaviorSpecification"): listener.exitBehaviorSpecification(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitBehaviorSpecification" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitBehaviorSpecification"): return visitor.visitBehaviorSpecification(self) else: return visitor.visitChildren(self) - - - def behaviorSpecification(self): localctx = OpenSCENARIO2Parser.BehaviorSpecificationContext(self, self._ctx, self.state) @@ -7067,17 +6538,15 @@ def behaviorSpecification(self): self.exitRule() return localctx - class OnDirectiveContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def eventSpecification(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.EventSpecificationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.EventSpecificationContext, 0) def NEWLINE(self): return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) @@ -7088,38 +6557,34 @@ def INDENT(self): def DEDENT(self): return self.getToken(OpenSCENARIO2Parser.DEDENT, 0) - def onMember(self, i:int=None): + def onMember(self, i: int = None): if i is None: return self.getTypedRuleContexts(OpenSCENARIO2Parser.OnMemberContext) else: - return self.getTypedRuleContext(OpenSCENARIO2Parser.OnMemberContext,i) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.OnMemberContext, i) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_onDirective - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterOnDirective" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterOnDirective"): listener.enterOnDirective(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitOnDirective" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitOnDirective"): listener.exitOnDirective(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitOnDirective" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitOnDirective"): return visitor.visitOnDirective(self) else: return visitor.visitChildren(self) - - - def onDirective(self): localctx = OpenSCENARIO2Parser.OnDirectiveContext(self, self._ctx, self.state) self.enterRule(localctx, 172, self.RULE_onDirective) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 876 @@ -7132,16 +6597,16 @@ def onDirective(self): self.match(OpenSCENARIO2Parser.NEWLINE) self.state = 880 self.match(OpenSCENARIO2Parser.INDENT) - self.state = 882 + self.state = 882 self._errHandler.sync(self) _la = self._input.LA(1) while True: self.state = 881 self.onMember() - self.state = 884 + self.state = 884 self._errHandler.sync(self) _la = self._input.LA(1) - if not (_la==OpenSCENARIO2Parser.T__61 or _la==OpenSCENARIO2Parser.T__62): + if not (_la == OpenSCENARIO2Parser.T__61 or _la == OpenSCENARIO2Parser.T__62): break self.state = 886 @@ -7154,42 +6619,36 @@ def onDirective(self): self.exitRule() return localctx - class OnMemberContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def callDirective(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.CallDirectiveContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.CallDirectiveContext, 0) def emitDirective(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.EmitDirectiveContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.EmitDirectiveContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_onMember - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterOnMember" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterOnMember"): listener.enterOnMember(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitOnMember" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitOnMember"): listener.exitOnMember(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitOnMember" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitOnMember"): return visitor.visitOnMember(self) else: return visitor.visitChildren(self) - - - def onMember(self): localctx = OpenSCENARIO2Parser.OnMemberContext(self, self._ctx, self.state) @@ -7219,38 +6678,33 @@ def onMember(self): self.exitRule() return localctx - class DoDirectiveContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def doMember(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.DoMemberContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.DoMemberContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_doDirective - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterDoDirective" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterDoDirective"): listener.enterDoDirective(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitDoDirective" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitDoDirective"): listener.exitDoDirective(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitDoDirective" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitDoDirective"): return visitor.visitDoDirective(self) else: return visitor.visitChildren(self) - - - def doDirective(self): localctx = OpenSCENARIO2Parser.DoDirectiveContext(self, self._ctx, self.state) @@ -7269,58 +6723,48 @@ def doDirective(self): self.exitRule() return localctx - class DoMemberContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def composition(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.CompositionContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.CompositionContext, 0) def behaviorInvocation(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.BehaviorInvocationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.BehaviorInvocationContext, 0) def waitDirective(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.WaitDirectiveContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.WaitDirectiveContext, 0) def emitDirective(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.EmitDirectiveContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.EmitDirectiveContext, 0) def callDirective(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.CallDirectiveContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.CallDirectiveContext, 0) def labelName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.LabelNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.LabelNameContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_doMember - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterDoMember" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterDoMember"): listener.enterDoMember(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitDoMember" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitDoMember"): listener.exitDoMember(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitDoMember" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitDoMember"): return visitor.visitDoMember(self) else: return visitor.visitChildren(self) - - - def doMember(self): localctx = OpenSCENARIO2Parser.DoMemberContext(self, self._ctx, self.state) @@ -7329,14 +6773,13 @@ def doMember(self): self.enterOuterAlt(localctx, 1) self.state = 898 self._errHandler.sync(self) - la_ = self._interp.adaptivePredict(self._input,78,self._ctx) + la_ = self._interp.adaptivePredict(self._input, 78, self._ctx) if la_ == 1: self.state = 895 self.labelName() self.state = 896 self.match(OpenSCENARIO2Parser.T__8) - self.state = 905 self._errHandler.sync(self) token = self._input.LA(1) @@ -7371,17 +6814,15 @@ def doMember(self): self.exitRule() return localctx - class CompositionContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def compositionOperator(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.CompositionOperatorContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.CompositionOperatorContext, 0) def NEWLINE(self): return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) @@ -7398,46 +6839,40 @@ def OPEN_PAREN(self): def CLOSE_PAREN(self): return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) - def doMember(self, i:int=None): + def doMember(self, i: int = None): if i is None: return self.getTypedRuleContexts(OpenSCENARIO2Parser.DoMemberContext) else: - return self.getTypedRuleContext(OpenSCENARIO2Parser.DoMemberContext,i) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.DoMemberContext, i) def behaviorWithDeclaration(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.BehaviorWithDeclarationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.BehaviorWithDeclarationContext, 0) def argumentList(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ArgumentListContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ArgumentListContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_composition - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterComposition" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterComposition"): listener.enterComposition(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitComposition" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitComposition"): listener.exitComposition(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitComposition" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitComposition"): return visitor.visitComposition(self) else: return visitor.visitChildren(self) - - - def composition(self): localctx = OpenSCENARIO2Parser.CompositionContext(self, self._ctx, self.state) self.enterRule(localctx, 180, self.RULE_composition) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 907 @@ -7445,7 +6880,7 @@ def composition(self): self.state = 913 self._errHandler.sync(self) _la = self._input.LA(1) - if _la==OpenSCENARIO2Parser.OPEN_PAREN: + if _la == OpenSCENARIO2Parser.OPEN_PAREN: self.state = 908 self.match(OpenSCENARIO2Parser.OPEN_PAREN) self.state = 910 @@ -7455,24 +6890,22 @@ def composition(self): self.state = 909 self.argumentList() - self.state = 912 self.match(OpenSCENARIO2Parser.CLOSE_PAREN) - self.state = 915 self.match(OpenSCENARIO2Parser.T__8) self.state = 916 self.match(OpenSCENARIO2Parser.NEWLINE) self.state = 917 self.match(OpenSCENARIO2Parser.INDENT) - self.state = 919 + self.state = 919 self._errHandler.sync(self) _la = self._input.LA(1) while True: self.state = 918 self.doMember() - self.state = 921 + self.state = 921 self._errHandler.sync(self) _la = self._input.LA(1) if not (((((_la - 55)) & ~0x3f) == 0 and ((1 << (_la - 55)) & ((1 << (OpenSCENARIO2Parser.T__54 - 55)) | (1 << (OpenSCENARIO2Parser.T__55 - 55)) | (1 << (OpenSCENARIO2Parser.T__56 - 55)) | (1 << (OpenSCENARIO2Parser.T__57 - 55)) | (1 << (OpenSCENARIO2Parser.T__58 - 55)) | (1 << (OpenSCENARIO2Parser.T__59 - 55)) | (1 << (OpenSCENARIO2Parser.T__60 - 55)) | (1 << (OpenSCENARIO2Parser.T__61 - 55)) | (1 << (OpenSCENARIO2Parser.T__62 - 55)) | (1 << (OpenSCENARIO2Parser.Identifier - 55)))) != 0)): @@ -7483,11 +6916,10 @@ def composition(self): self.state = 925 self._errHandler.sync(self) _la = self._input.LA(1) - if _la==OpenSCENARIO2Parser.T__47: + if _la == OpenSCENARIO2Parser.T__47: self.state = 924 self.behaviorWithDeclaration() - except RecognitionException as re: localctx.exception = re self._errHandler.reportError(self, re) @@ -7496,40 +6928,35 @@ def composition(self): self.exitRule() return localctx - class CompositionOperatorContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser - def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_compositionOperator - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterCompositionOperator" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterCompositionOperator"): listener.enterCompositionOperator(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitCompositionOperator" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitCompositionOperator"): listener.exitCompositionOperator(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitCompositionOperator" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitCompositionOperator"): return visitor.visitCompositionOperator(self) else: return visitor.visitChildren(self) - - - def compositionOperator(self): localctx = OpenSCENARIO2Parser.CompositionOperatorContext(self, self._ctx, self.state) self.enterRule(localctx, 182, self.RULE_compositionOperator) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 927 @@ -7547,17 +6974,15 @@ def compositionOperator(self): self.exitRule() return localctx - class BehaviorInvocationContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def behaviorName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.BehaviorNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.BehaviorNameContext, 0) def OPEN_PAREN(self): return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) @@ -7566,57 +6991,50 @@ def CLOSE_PAREN(self): return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) def behaviorWithDeclaration(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.BehaviorWithDeclarationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.BehaviorWithDeclarationContext, 0) def NEWLINE(self): return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) def actorExpression(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ActorExpressionContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ActorExpressionContext, 0) def argumentList(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ArgumentListContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ArgumentListContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_behaviorInvocation - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterBehaviorInvocation" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterBehaviorInvocation"): listener.enterBehaviorInvocation(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitBehaviorInvocation" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitBehaviorInvocation"): listener.exitBehaviorInvocation(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitBehaviorInvocation" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitBehaviorInvocation"): return visitor.visitBehaviorInvocation(self) else: return visitor.visitChildren(self) - - - def behaviorInvocation(self): localctx = OpenSCENARIO2Parser.BehaviorInvocationContext(self, self._ctx, self.state) self.enterRule(localctx, 184, self.RULE_behaviorInvocation) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 932 self._errHandler.sync(self) - la_ = self._interp.adaptivePredict(self._input,84,self._ctx) + la_ = self._interp.adaptivePredict(self._input, 84, self._ctx) if la_ == 1: self.state = 929 self.actorExpression() self.state = 930 self.match(OpenSCENARIO2Parser.T__1) - self.state = 934 self.behaviorName() self.state = 935 @@ -7628,7 +7046,6 @@ def behaviorInvocation(self): self.state = 936 self.argumentList() - self.state = 939 self.match(OpenSCENARIO2Parser.CLOSE_PAREN) self.state = 942 @@ -7653,11 +7070,10 @@ def behaviorInvocation(self): self.exitRule() return localctx - class BehaviorWithDeclarationContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser @@ -7670,38 +7086,34 @@ def INDENT(self): def DEDENT(self): return self.getToken(OpenSCENARIO2Parser.DEDENT, 0) - def behaviorWithMember(self, i:int=None): + def behaviorWithMember(self, i: int = None): if i is None: return self.getTypedRuleContexts(OpenSCENARIO2Parser.BehaviorWithMemberContext) else: - return self.getTypedRuleContext(OpenSCENARIO2Parser.BehaviorWithMemberContext,i) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.BehaviorWithMemberContext, i) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_behaviorWithDeclaration - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterBehaviorWithDeclaration" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterBehaviorWithDeclaration"): listener.enterBehaviorWithDeclaration(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitBehaviorWithDeclaration" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitBehaviorWithDeclaration"): listener.exitBehaviorWithDeclaration(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitBehaviorWithDeclaration" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitBehaviorWithDeclaration"): return visitor.visitBehaviorWithDeclaration(self) else: return visitor.visitChildren(self) - - - def behaviorWithDeclaration(self): localctx = OpenSCENARIO2Parser.BehaviorWithDeclarationContext(self, self._ctx, self.state) self.enterRule(localctx, 186, self.RULE_behaviorWithDeclaration) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 944 @@ -7712,13 +7124,13 @@ def behaviorWithDeclaration(self): self.match(OpenSCENARIO2Parser.NEWLINE) self.state = 947 self.match(OpenSCENARIO2Parser.INDENT) - self.state = 949 + self.state = 949 self._errHandler.sync(self) _la = self._input.LA(1) while True: self.state = 948 self.behaviorWithMember() - self.state = 951 + self.state = 951 self._errHandler.sync(self) _la = self._input.LA(1) if not (((((_la - 49)) & ~0x3f) == 0 and ((1 << (_la - 49)) & ((1 << (OpenSCENARIO2Parser.T__48 - 49)) | (1 << (OpenSCENARIO2Parser.T__51 - 49)) | (1 << (OpenSCENARIO2Parser.T__63 - 49)) | (1 << (OpenSCENARIO2Parser.Identifier - 49)))) != 0)): @@ -7734,46 +7146,39 @@ def behaviorWithDeclaration(self): self.exitRule() return localctx - class BehaviorWithMemberContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def constraintDeclaration(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ConstraintDeclarationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ConstraintDeclarationContext, 0) def modifierInvocation(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ModifierInvocationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ModifierInvocationContext, 0) def untilDirective(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.UntilDirectiveContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.UntilDirectiveContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_behaviorWithMember - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterBehaviorWithMember" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterBehaviorWithMember"): listener.enterBehaviorWithMember(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitBehaviorWithMember" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitBehaviorWithMember"): listener.exitBehaviorWithMember(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitBehaviorWithMember" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitBehaviorWithMember"): return visitor.visitBehaviorWithMember(self) else: return visitor.visitChildren(self) - - - def behaviorWithMember(self): localctx = OpenSCENARIO2Parser.BehaviorWithMemberContext(self, self._ctx, self.state) @@ -7808,11 +7213,10 @@ def behaviorWithMember(self): self.exitRule() return localctx - class LabelNameContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser @@ -7822,23 +7226,20 @@ def Identifier(self): def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_labelName - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterLabelName" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterLabelName"): listener.enterLabelName(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitLabelName" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitLabelName"): listener.exitLabelName(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitLabelName" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitLabelName"): return visitor.visitLabelName(self) else: return visitor.visitChildren(self) - - - def labelName(self): localctx = OpenSCENARIO2Parser.LabelNameContext(self, self._ctx, self.state) @@ -7855,38 +7256,33 @@ def labelName(self): self.exitRule() return localctx - class ActorExpressionContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def actorName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ActorNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ActorNameContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_actorExpression - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterActorExpression" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterActorExpression"): listener.enterActorExpression(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitActorExpression" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitActorExpression"): listener.exitActorExpression(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitActorExpression" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitActorExpression"): return visitor.visitActorExpression(self) else: return visitor.visitChildren(self) - - - def actorExpression(self): localctx = OpenSCENARIO2Parser.ActorExpressionContext(self, self._ctx, self.state) @@ -7903,17 +7299,15 @@ def actorExpression(self): self.exitRule() return localctx - class WaitDirectiveContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def eventSpecification(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.EventSpecificationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.EventSpecificationContext, 0) def NEWLINE(self): return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) @@ -7921,23 +7315,20 @@ def NEWLINE(self): def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_waitDirective - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterWaitDirective" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterWaitDirective"): listener.enterWaitDirective(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitWaitDirective" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitWaitDirective"): listener.exitWaitDirective(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitWaitDirective" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitWaitDirective"): return visitor.visitWaitDirective(self) else: return visitor.visitChildren(self) - - - def waitDirective(self): localctx = OpenSCENARIO2Parser.WaitDirectiveContext(self, self._ctx, self.state) @@ -7958,17 +7349,15 @@ def waitDirective(self): self.exitRule() return localctx - class EmitDirectiveContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def eventName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.EventNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.EventNameContext, 0) def NEWLINE(self): return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) @@ -7977,8 +7366,7 @@ def OPEN_PAREN(self): return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) def argumentList(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ArgumentListContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ArgumentListContext, 0) def CLOSE_PAREN(self): return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) @@ -7986,28 +7374,25 @@ def CLOSE_PAREN(self): def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_emitDirective - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterEmitDirective" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterEmitDirective"): listener.enterEmitDirective(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitEmitDirective" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitEmitDirective"): listener.exitEmitDirective(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitEmitDirective" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitEmitDirective"): return visitor.visitEmitDirective(self) else: return visitor.visitChildren(self) - - - def emitDirective(self): localctx = OpenSCENARIO2Parser.EmitDirectiveContext(self, self._ctx, self.state) self.enterRule(localctx, 196, self.RULE_emitDirective) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 968 @@ -8017,7 +7402,7 @@ def emitDirective(self): self.state = 974 self._errHandler.sync(self) _la = self._input.LA(1) - if _la==OpenSCENARIO2Parser.OPEN_PAREN: + if _la == OpenSCENARIO2Parser.OPEN_PAREN: self.state = 970 self.match(OpenSCENARIO2Parser.OPEN_PAREN) self.state = 971 @@ -8025,7 +7410,6 @@ def emitDirective(self): self.state = 972 self.match(OpenSCENARIO2Parser.CLOSE_PAREN) - self.state = 976 self.match(OpenSCENARIO2Parser.NEWLINE) except RecognitionException as re: @@ -8036,17 +7420,15 @@ def emitDirective(self): self.exitRule() return localctx - class CallDirectiveContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def methodInvocation(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.MethodInvocationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.MethodInvocationContext, 0) def NEWLINE(self): return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) @@ -8054,23 +7436,20 @@ def NEWLINE(self): def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_callDirective - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterCallDirective" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterCallDirective"): listener.enterCallDirective(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitCallDirective" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitCallDirective"): listener.exitCallDirective(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitCallDirective" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitCallDirective"): return visitor.visitCallDirective(self) else: return visitor.visitChildren(self) - - - def callDirective(self): localctx = OpenSCENARIO2Parser.CallDirectiveContext(self, self._ctx, self.state) @@ -8091,17 +7470,15 @@ def callDirective(self): self.exitRule() return localctx - class UntilDirectiveContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def eventSpecification(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.EventSpecificationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.EventSpecificationContext, 0) def NEWLINE(self): return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) @@ -8109,23 +7486,20 @@ def NEWLINE(self): def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_untilDirective - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterUntilDirective" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterUntilDirective"): listener.enterUntilDirective(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitUntilDirective" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitUntilDirective"): listener.exitUntilDirective(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitUntilDirective" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitUntilDirective"): return visitor.visitUntilDirective(self) else: return visitor.visitChildren(self) - - - def untilDirective(self): localctx = OpenSCENARIO2Parser.UntilDirectiveContext(self, self._ctx, self.state) @@ -8146,17 +7520,15 @@ def untilDirective(self): self.exitRule() return localctx - class MethodInvocationContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def postfixExp(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.PostfixExpContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.PostfixExpContext, 0) def OPEN_PAREN(self): return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) @@ -8165,34 +7537,30 @@ def CLOSE_PAREN(self): return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) def argumentList(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ArgumentListContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ArgumentListContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_methodInvocation - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterMethodInvocation" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterMethodInvocation"): listener.enterMethodInvocation(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitMethodInvocation" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitMethodInvocation"): listener.exitMethodInvocation(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitMethodInvocation" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitMethodInvocation"): return visitor.visitMethodInvocation(self) else: return visitor.visitChildren(self) - - - def methodInvocation(self): localctx = OpenSCENARIO2Parser.MethodInvocationContext(self, self._ctx, self.state) self.enterRule(localctx, 202, self.RULE_methodInvocation) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 986 @@ -8206,7 +7574,6 @@ def methodInvocation(self): self.state = 988 self.argumentList() - self.state = 991 self.match(OpenSCENARIO2Parser.CLOSE_PAREN) except RecognitionException as re: @@ -8217,17 +7584,15 @@ def methodInvocation(self): self.exitRule() return localctx - class MethodDeclarationContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def methodName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.MethodNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.MethodNameContext, 0) def OPEN_PAREN(self): return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) @@ -8236,45 +7601,39 @@ def CLOSE_PAREN(self): return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) def methodImplementation(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.MethodImplementationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.MethodImplementationContext, 0) def NEWLINE(self): return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) def argumentListSpecification(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ArgumentListSpecificationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ArgumentListSpecificationContext, 0) def returnType(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ReturnTypeContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ReturnTypeContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_methodDeclaration - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterMethodDeclaration" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterMethodDeclaration"): listener.enterMethodDeclaration(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitMethodDeclaration" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitMethodDeclaration"): listener.exitMethodDeclaration(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitMethodDeclaration" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitMethodDeclaration"): return visitor.visitMethodDeclaration(self) else: return visitor.visitChildren(self) - - - def methodDeclaration(self): localctx = OpenSCENARIO2Parser.MethodDeclarationContext(self, self._ctx, self.state) self.enterRule(localctx, 204, self.RULE_methodDeclaration) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 993 @@ -8286,23 +7645,21 @@ def methodDeclaration(self): self.state = 997 self._errHandler.sync(self) _la = self._input.LA(1) - if _la==OpenSCENARIO2Parser.Identifier: + if _la == OpenSCENARIO2Parser.Identifier: self.state = 996 self.argumentListSpecification() - self.state = 999 self.match(OpenSCENARIO2Parser.CLOSE_PAREN) self.state = 1002 self._errHandler.sync(self) _la = self._input.LA(1) - if _la==OpenSCENARIO2Parser.T__65: + if _la == OpenSCENARIO2Parser.T__65: self.state = 1000 self.match(OpenSCENARIO2Parser.T__65) self.state = 1001 self.returnType() - self.state = 1004 self.methodImplementation() self.state = 1005 @@ -8315,38 +7672,33 @@ def methodDeclaration(self): self.exitRule() return localctx - class ReturnTypeContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def typeDeclarator(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.TypeDeclaratorContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.TypeDeclaratorContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_returnType - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterReturnType" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterReturnType"): listener.enterReturnType(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitReturnType" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitReturnType"): listener.exitReturnType(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitReturnType" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitReturnType"): return visitor.visitReturnType(self) else: return visitor.visitChildren(self) - - - def returnType(self): localctx = OpenSCENARIO2Parser.ReturnTypeContext(self, self._ctx, self.state) @@ -8363,21 +7715,18 @@ def returnType(self): self.exitRule() return localctx - class MethodImplementationContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def expression(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext, 0) def structuredIdentifier(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.StructuredIdentifierContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.StructuredIdentifierContext, 0) def OPEN_PAREN(self): return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) @@ -8386,38 +7735,33 @@ def CLOSE_PAREN(self): return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) def methodQualifier(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.MethodQualifierContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.MethodQualifierContext, 0) def argumentList(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ArgumentListContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ArgumentListContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_methodImplementation - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterMethodImplementation" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterMethodImplementation"): listener.enterMethodImplementation(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitMethodImplementation" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitMethodImplementation"): listener.exitMethodImplementation(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitMethodImplementation" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitMethodImplementation"): return visitor.visitMethodImplementation(self) else: return visitor.visitChildren(self) - - - def methodImplementation(self): localctx = OpenSCENARIO2Parser.MethodImplementationContext(self, self._ctx, self.state) self.enterRule(localctx, 208, self.RULE_methodImplementation) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 1009 @@ -8425,11 +7769,10 @@ def methodImplementation(self): self.state = 1011 self._errHandler.sync(self) _la = self._input.LA(1) - if _la==OpenSCENARIO2Parser.T__69: + if _la == OpenSCENARIO2Parser.T__69: self.state = 1010 self.methodQualifier() - self.state = 1024 self._errHandler.sync(self) token = self._input.LA(1) @@ -8457,7 +7800,6 @@ def methodImplementation(self): self.state = 1019 self.argumentList() - self.state = 1022 self.match(OpenSCENARIO2Parser.CLOSE_PAREN) pass @@ -8472,35 +7814,30 @@ def methodImplementation(self): self.exitRule() return localctx - class MethodQualifierContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser - def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_methodQualifier - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterMethodQualifier" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterMethodQualifier"): listener.enterMethodQualifier(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitMethodQualifier" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitMethodQualifier"): listener.exitMethodQualifier(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitMethodQualifier" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitMethodQualifier"): return visitor.visitMethodQualifier(self) else: return visitor.visitChildren(self) - - - def methodQualifier(self): localctx = OpenSCENARIO2Parser.MethodQualifierContext(self, self._ctx, self.state) @@ -8517,11 +7854,10 @@ def methodQualifier(self): self.exitRule() return localctx - class MethodNameContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser @@ -8531,23 +7867,20 @@ def Identifier(self): def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_methodName - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterMethodName" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterMethodName"): listener.enterMethodName(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitMethodName" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitMethodName"): listener.exitMethodName(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitMethodName" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitMethodName"): return visitor.visitMethodName(self) else: return visitor.visitChildren(self) - - - def methodName(self): localctx = OpenSCENARIO2Parser.MethodNameContext(self, self._ctx, self.state) @@ -8564,42 +7897,36 @@ def methodName(self): self.exitRule() return localctx - class CoverageDeclarationContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def coverDeclaration(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.CoverDeclarationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.CoverDeclarationContext, 0) def recordDeclaration(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.RecordDeclarationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.RecordDeclarationContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_coverageDeclaration - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterCoverageDeclaration" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterCoverageDeclaration"): listener.enterCoverageDeclaration(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitCoverageDeclaration" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitCoverageDeclaration"): listener.exitCoverageDeclaration(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitCoverageDeclaration" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitCoverageDeclaration"): return visitor.visitCoverageDeclaration(self) else: return visitor.visitChildren(self) - - - def coverageDeclaration(self): localctx = OpenSCENARIO2Parser.CoverageDeclarationContext(self, self._ctx, self.state) @@ -8629,11 +7956,10 @@ def coverageDeclaration(self): self.exitRule() return localctx - class CoverDeclarationContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser @@ -8647,41 +7973,36 @@ def NEWLINE(self): return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) def targetName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.TargetNameContext,0) + return self.getTypedRuleContext(OpenSCENARIO2Parser.TargetNameContext, 0) - - def coverageArgumentList(self, i:int=None): + def coverageArgumentList(self, i: int = None): if i is None: return self.getTypedRuleContexts(OpenSCENARIO2Parser.CoverageArgumentListContext) else: - return self.getTypedRuleContext(OpenSCENARIO2Parser.CoverageArgumentListContext,i) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.CoverageArgumentListContext, i) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_coverDeclaration - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterCoverDeclaration" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterCoverDeclaration"): listener.enterCoverDeclaration(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitCoverDeclaration" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitCoverDeclaration"): listener.exitCoverDeclaration(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitCoverDeclaration" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitCoverDeclaration"): return visitor.visitCoverDeclaration(self) else: return visitor.visitChildren(self) - - - def coverDeclaration(self): localctx = OpenSCENARIO2Parser.CoverDeclarationContext(self, self._ctx, self.state) self.enterRule(localctx, 216, self.RULE_coverDeclaration) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 1034 @@ -8691,15 +8012,14 @@ def coverDeclaration(self): self.state = 1037 self._errHandler.sync(self) _la = self._input.LA(1) - if _la==OpenSCENARIO2Parser.Identifier: + if _la == OpenSCENARIO2Parser.Identifier: self.state = 1036 self.targetName() - self.state = 1042 self._errHandler.sync(self) _la = self._input.LA(1) - while _la==OpenSCENARIO2Parser.T__7: + while _la == OpenSCENARIO2Parser.T__7: self.state = 1039 self.coverageArgumentList() self.state = 1044 @@ -8718,11 +8038,10 @@ def coverDeclaration(self): self.exitRule() return localctx - class RecordDeclarationContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser @@ -8736,41 +8055,36 @@ def NEWLINE(self): return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) def targetName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.TargetNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.TargetNameContext, 0) - def coverageArgumentList(self, i:int=None): + def coverageArgumentList(self, i: int = None): if i is None: return self.getTypedRuleContexts(OpenSCENARIO2Parser.CoverageArgumentListContext) else: - return self.getTypedRuleContext(OpenSCENARIO2Parser.CoverageArgumentListContext,i) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.CoverageArgumentListContext, i) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_recordDeclaration - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterRecordDeclaration" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterRecordDeclaration"): listener.enterRecordDeclaration(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitRecordDeclaration" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitRecordDeclaration"): listener.exitRecordDeclaration(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitRecordDeclaration" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitRecordDeclaration"): return visitor.visitRecordDeclaration(self) else: return visitor.visitChildren(self) - - - def recordDeclaration(self): localctx = OpenSCENARIO2Parser.RecordDeclarationContext(self, self._ctx, self.state) self.enterRule(localctx, 218, self.RULE_recordDeclaration) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 1048 @@ -8780,15 +8094,14 @@ def recordDeclaration(self): self.state = 1051 self._errHandler.sync(self) _la = self._input.LA(1) - if _la==OpenSCENARIO2Parser.Identifier: + if _la == OpenSCENARIO2Parser.Identifier: self.state = 1050 self.targetName() - self.state = 1056 self._errHandler.sync(self) _la = self._input.LA(1) - while _la==OpenSCENARIO2Parser.T__7: + while _la == OpenSCENARIO2Parser.T__7: self.state = 1053 self.coverageArgumentList() self.state = 1058 @@ -8807,175 +8120,157 @@ def recordDeclaration(self): self.exitRule() return localctx - class CoverageArgumentListContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser - def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_coverageArgumentList - - def copyFrom(self, ctx:ParserRuleContext): + def copyFrom(self, ctx: ParserRuleContext): super().copyFrom(ctx) - - class CoverageEventContext(CoverageArgumentListContext): - def __init__(self, parser, ctx:ParserRuleContext): # actually a OpenSCENARIO2Parser.CoverageArgumentListContext + def __init__(self, parser, ctx: ParserRuleContext): # actually a OpenSCENARIO2Parser.CoverageArgumentListContext super().__init__(parser) self.copyFrom(ctx) def eventName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.EventNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.EventNameContext, 0) - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterCoverageEvent" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterCoverageEvent"): listener.enterCoverageEvent(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitCoverageEvent" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitCoverageEvent"): listener.exitCoverageEvent(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitCoverageEvent" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitCoverageEvent"): return visitor.visitCoverageEvent(self) else: return visitor.visitChildren(self) - class CoverageEveryContext(CoverageArgumentListContext): - def __init__(self, parser, ctx:ParserRuleContext): # actually a OpenSCENARIO2Parser.CoverageArgumentListContext + def __init__(self, parser, ctx: ParserRuleContext): # actually a OpenSCENARIO2Parser.CoverageArgumentListContext super().__init__(parser) self.copyFrom(ctx) def valueExp(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ValueExpContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ValueExpContext, 0) - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterCoverageEvery" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterCoverageEvery"): listener.enterCoverageEvery(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitCoverageEvery" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitCoverageEvery"): listener.exitCoverageEvery(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitCoverageEvery" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitCoverageEvery"): return visitor.visitCoverageEvery(self) else: return visitor.visitChildren(self) - class CoverageNameArgumentContext(CoverageArgumentListContext): - def __init__(self, parser, ctx:ParserRuleContext): # actually a OpenSCENARIO2Parser.CoverageArgumentListContext + def __init__(self, parser, ctx: ParserRuleContext): # actually a OpenSCENARIO2Parser.CoverageArgumentListContext super().__init__(parser) self.copyFrom(ctx) def namedArgument(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.NamedArgumentContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.NamedArgumentContext, 0) - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterCoverageNameArgument" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterCoverageNameArgument"): listener.enterCoverageNameArgument(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitCoverageNameArgument" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitCoverageNameArgument"): listener.exitCoverageNameArgument(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitCoverageNameArgument" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitCoverageNameArgument"): return visitor.visitCoverageNameArgument(self) else: return visitor.visitChildren(self) - class CoverageExpressionContext(CoverageArgumentListContext): - def __init__(self, parser, ctx:ParserRuleContext): # actually a OpenSCENARIO2Parser.CoverageArgumentListContext + def __init__(self, parser, ctx: ParserRuleContext): # actually a OpenSCENARIO2Parser.CoverageArgumentListContext super().__init__(parser) self.copyFrom(ctx) def expression(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext, 0) - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterCoverageExpression" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterCoverageExpression"): listener.enterCoverageExpression(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitCoverageExpression" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitCoverageExpression"): listener.exitCoverageExpression(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitCoverageExpression" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitCoverageExpression"): return visitor.visitCoverageExpression(self) else: return visitor.visitChildren(self) - class CoverageRangeContext(CoverageArgumentListContext): - def __init__(self, parser, ctx:ParserRuleContext): # actually a OpenSCENARIO2Parser.CoverageArgumentListContext + def __init__(self, parser, ctx: ParserRuleContext): # actually a OpenSCENARIO2Parser.CoverageArgumentListContext super().__init__(parser) self.copyFrom(ctx) def rangeConstructor(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.RangeConstructorContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.RangeConstructorContext, 0) - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterCoverageRange" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterCoverageRange"): listener.enterCoverageRange(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitCoverageRange" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitCoverageRange"): listener.exitCoverageRange(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitCoverageRange" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitCoverageRange"): return visitor.visitCoverageRange(self) else: return visitor.visitChildren(self) - class CoverageUnitContext(CoverageArgumentListContext): - def __init__(self, parser, ctx:ParserRuleContext): # actually a OpenSCENARIO2Parser.CoverageArgumentListContext + def __init__(self, parser, ctx: ParserRuleContext): # actually a OpenSCENARIO2Parser.CoverageArgumentListContext super().__init__(parser) self.copyFrom(ctx) def unitName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.UnitNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.UnitNameContext, 0) - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterCoverageUnit" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterCoverageUnit"): listener.enterCoverageUnit(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitCoverageUnit" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitCoverageUnit"): listener.exitCoverageUnit(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitCoverageUnit" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitCoverageUnit"): return visitor.visitCoverageUnit(self) else: return visitor.visitChildren(self) - - def coverageArgumentList(self): localctx = OpenSCENARIO2Parser.CoverageArgumentListContext(self, self._ctx, self.state) @@ -8983,7 +8278,7 @@ def coverageArgumentList(self): try: self.state = 1084 self._errHandler.sync(self) - la_ = self._interp.adaptivePredict(self._input,101,self._ctx) + la_ = self._interp.adaptivePredict(self._input, 101, self._ctx) if la_ == 1: localctx = OpenSCENARIO2Parser.CoverageExpressionContext(self, localctx) self.enterOuterAlt(localctx, 1) @@ -9058,7 +8353,6 @@ def coverageArgumentList(self): self.namedArgument() pass - except RecognitionException as re: localctx.exception = re self._errHandler.reportError(self, re) @@ -9067,11 +8361,10 @@ def coverageArgumentList(self): self.exitRule() return localctx - class TargetNameContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser @@ -9081,23 +8374,20 @@ def Identifier(self): def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_targetName - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterTargetName" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterTargetName"): listener.enterTargetName(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitTargetName" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitTargetName"): listener.exitTargetName(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitTargetName" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitTargetName"): return visitor.visitTargetName(self) else: return visitor.visitChildren(self) - - - def targetName(self): localctx = OpenSCENARIO2Parser.TargetNameContext(self, self._ctx, self.state) @@ -9114,42 +8404,36 @@ def targetName(self): self.exitRule() return localctx - class ExpressionContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def implication(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ImplicationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ImplicationContext, 0) def ternaryOpExp(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.TernaryOpExpContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.TernaryOpExpContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_expression - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterExpression" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterExpression"): listener.enterExpression(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitExpression" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitExpression"): listener.exitExpression(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitExpression" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitExpression"): return visitor.visitExpression(self) else: return visitor.visitChildren(self) - - - def expression(self): localctx = OpenSCENARIO2Parser.ExpressionContext(self, self._ctx, self.state) @@ -9157,7 +8441,7 @@ def expression(self): try: self.state = 1090 self._errHandler.sync(self) - la_ = self._interp.adaptivePredict(self._input,102,self._ctx) + la_ = self._interp.adaptivePredict(self._input, 102, self._ctx) if la_ == 1: self.enterOuterAlt(localctx, 1) self.state = 1088 @@ -9170,7 +8454,6 @@ def expression(self): self.ternaryOpExp() pass - except RecognitionException as re: localctx.exception = re self._errHandler.reportError(self, re) @@ -9179,45 +8462,39 @@ def expression(self): self.exitRule() return localctx - class TernaryOpExpContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def implication(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ImplicationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ImplicationContext, 0) - def expression(self, i:int=None): + def expression(self, i: int = None): if i is None: return self.getTypedRuleContexts(OpenSCENARIO2Parser.ExpressionContext) else: - return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext,i) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext, i) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_ternaryOpExp - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterTernaryOpExp" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterTernaryOpExp"): listener.enterTernaryOpExp(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitTernaryOpExp" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitTernaryOpExp"): listener.exitTernaryOpExp(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitTernaryOpExp" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitTernaryOpExp"): return visitor.visitTernaryOpExp(self) else: return visitor.visitChildren(self) - - - def ternaryOpExp(self): localctx = OpenSCENARIO2Parser.TernaryOpExpContext(self, self._ctx, self.state) @@ -9242,46 +8519,41 @@ def ternaryOpExp(self): self.exitRule() return localctx - class ImplicationContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser - def disjunction(self, i:int=None): + def disjunction(self, i: int = None): if i is None: return self.getTypedRuleContexts(OpenSCENARIO2Parser.DisjunctionContext) else: - return self.getTypedRuleContext(OpenSCENARIO2Parser.DisjunctionContext,i) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.DisjunctionContext, i) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_implication - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterImplication" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterImplication"): listener.enterImplication(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitImplication" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitImplication"): listener.exitImplication(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitImplication" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitImplication"): return visitor.visitImplication(self) else: return visitor.visitChildren(self) - - - def implication(self): localctx = OpenSCENARIO2Parser.ImplicationContext(self, self._ctx, self.state) self.enterRule(localctx, 228, self.RULE_implication) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 1098 @@ -9289,7 +8561,7 @@ def implication(self): self.state = 1103 self._errHandler.sync(self) _la = self._input.LA(1) - while _la==OpenSCENARIO2Parser.T__74: + while _la == OpenSCENARIO2Parser.T__74: self.state = 1099 self.match(OpenSCENARIO2Parser.T__74) self.state = 1100 @@ -9306,46 +8578,41 @@ def implication(self): self.exitRule() return localctx - class DisjunctionContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser - def conjunction(self, i:int=None): + def conjunction(self, i: int = None): if i is None: return self.getTypedRuleContexts(OpenSCENARIO2Parser.ConjunctionContext) else: - return self.getTypedRuleContext(OpenSCENARIO2Parser.ConjunctionContext,i) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ConjunctionContext, i) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_disjunction - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterDisjunction" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterDisjunction"): listener.enterDisjunction(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitDisjunction" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitDisjunction"): listener.exitDisjunction(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitDisjunction" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitDisjunction"): return visitor.visitDisjunction(self) else: return visitor.visitChildren(self) - - - def disjunction(self): localctx = OpenSCENARIO2Parser.DisjunctionContext(self, self._ctx, self.state) self.enterRule(localctx, 230, self.RULE_disjunction) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 1106 @@ -9353,7 +8620,7 @@ def disjunction(self): self.state = 1111 self._errHandler.sync(self) _la = self._input.LA(1) - while _la==OpenSCENARIO2Parser.T__75: + while _la == OpenSCENARIO2Parser.T__75: self.state = 1107 self.match(OpenSCENARIO2Parser.T__75) self.state = 1108 @@ -9370,46 +8637,41 @@ def disjunction(self): self.exitRule() return localctx - class ConjunctionContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser - def inversion(self, i:int=None): + def inversion(self, i: int = None): if i is None: return self.getTypedRuleContexts(OpenSCENARIO2Parser.InversionContext) else: - return self.getTypedRuleContext(OpenSCENARIO2Parser.InversionContext,i) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.InversionContext, i) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_conjunction - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterConjunction" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterConjunction"): listener.enterConjunction(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitConjunction" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitConjunction"): listener.exitConjunction(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitConjunction" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitConjunction"): return visitor.visitConjunction(self) else: return visitor.visitChildren(self) - - - def conjunction(self): localctx = OpenSCENARIO2Parser.ConjunctionContext(self, self._ctx, self.state) self.enterRule(localctx, 232, self.RULE_conjunction) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 1114 @@ -9417,7 +8679,7 @@ def conjunction(self): self.state = 1119 self._errHandler.sync(self) _la = self._input.LA(1) - while _la==OpenSCENARIO2Parser.T__76: + while _la == OpenSCENARIO2Parser.T__76: self.state = 1115 self.match(OpenSCENARIO2Parser.T__76) self.state = 1116 @@ -9434,42 +8696,36 @@ def conjunction(self): self.exitRule() return localctx - class InversionContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def inversion(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.InversionContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.InversionContext, 0) def relation(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.RelationContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.RelationContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_inversion - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterInversion" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterInversion"): listener.enterInversion(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitInversion" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitInversion"): listener.exitInversion(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitInversion" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitInversion"): return visitor.visitInversion(self) else: return visitor.visitChildren(self) - - - def inversion(self): localctx = OpenSCENARIO2Parser.InversionContext(self, self._ctx, self.state) @@ -9501,81 +8757,72 @@ def inversion(self): self.exitRule() return localctx - class RelationContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser - def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_relation - - def copyFrom(self, ctx:ParserRuleContext): + def copyFrom(self, ctx: ParserRuleContext): super().copyFrom(ctx) - class RelationExpContext(RelationContext): - def __init__(self, parser, ctx:ParserRuleContext): # actually a OpenSCENARIO2Parser.RelationContext + def __init__(self, parser, ctx: ParserRuleContext): # actually a OpenSCENARIO2Parser.RelationContext super().__init__(parser) self.copyFrom(ctx) def relation(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.RelationContext,0) + return self.getTypedRuleContext(OpenSCENARIO2Parser.RelationContext, 0) def relationalOp(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.RelationalOpContext,0) + return self.getTypedRuleContext(OpenSCENARIO2Parser.RelationalOpContext, 0) def sumExpression(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.SumExpressionContext,0) + return self.getTypedRuleContext(OpenSCENARIO2Parser.SumExpressionContext, 0) - - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterRelationExp" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterRelationExp"): listener.enterRelationExp(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitRelationExp" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitRelationExp"): listener.exitRelationExp(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitRelationExp" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitRelationExp"): return visitor.visitRelationExp(self) else: return visitor.visitChildren(self) - class SumExpContext(RelationContext): - def __init__(self, parser, ctx:ParserRuleContext): # actually a OpenSCENARIO2Parser.RelationContext + def __init__(self, parser, ctx: ParserRuleContext): # actually a OpenSCENARIO2Parser.RelationContext super().__init__(parser) self.copyFrom(ctx) def sumExpression(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.SumExpressionContext,0) + return self.getTypedRuleContext(OpenSCENARIO2Parser.SumExpressionContext, 0) - - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterSumExp" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterSumExp"): listener.enterSumExp(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitSumExp" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitSumExp"): listener.exitSumExp(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitSumExp" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitSumExp"): return visitor.visitSumExp(self) else: return visitor.visitChildren(self) - - - def relation(self, _p:int=0): + def relation(self, _p: int = 0): _parentctx = self._ctx _parentState = self.state localctx = OpenSCENARIO2Parser.RelationContext(self, self._ctx, _parentState) @@ -9593,13 +8840,14 @@ def relation(self, _p:int=0): self._ctx.stop = self._input.LT(-1) self.state = 1136 self._errHandler.sync(self) - _alt = self._interp.adaptivePredict(self._input,107,self._ctx) - while _alt!=2 and _alt!=ATN.INVALID_ALT_NUMBER: - if _alt==1: + _alt = self._interp.adaptivePredict(self._input, 107, self._ctx) + while _alt != 2 and _alt != ATN.INVALID_ALT_NUMBER: + if _alt == 1: if self._parseListeners is not None: self.triggerExitRuleEvent() _prevctx = localctx - localctx = OpenSCENARIO2Parser.RelationExpContext(self, OpenSCENARIO2Parser.RelationContext(self, _parentctx, _parentState)) + localctx = OpenSCENARIO2Parser.RelationExpContext( + self, OpenSCENARIO2Parser.RelationContext(self, _parentctx, _parentState)) self.pushNewRecursionContext(localctx, _startState, self.RULE_relation) self.state = 1130 if not self.precpred(self._ctx, 1): @@ -9608,10 +8856,10 @@ def relation(self, _p:int=0): self.state = 1131 self.relationalOp() self.state = 1132 - self.sumExpression(0) + self.sumExpression(0) self.state = 1138 self._errHandler.sync(self) - _alt = self._interp.adaptivePredict(self._input,107,self._ctx) + _alt = self._interp.adaptivePredict(self._input, 107, self._ctx) except RecognitionException as re: localctx.exception = re @@ -9621,40 +8869,35 @@ def relation(self, _p:int=0): self.unrollRecursionContexts(_parentctx) return localctx - class RelationalOpContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser - def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_relationalOp - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterRelationalOp" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterRelationalOp"): listener.enterRelationalOp(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitRelationalOp" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitRelationalOp"): listener.exitRelationalOp(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitRelationalOp" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitRelationalOp"): return visitor.visitRelationalOp(self) else: return visitor.visitChildren(self) - - - def relationalOp(self): localctx = OpenSCENARIO2Parser.RelationalOpContext(self, self._ctx, self.state) self.enterRule(localctx, 238, self.RULE_relationalOp) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 1139 @@ -9672,81 +8915,72 @@ def relationalOp(self): self.exitRule() return localctx - class SumExpressionContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser - def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_sumExpression - - def copyFrom(self, ctx:ParserRuleContext): + def copyFrom(self, ctx: ParserRuleContext): super().copyFrom(ctx) - class TermExpContext(SumExpressionContext): - def __init__(self, parser, ctx:ParserRuleContext): # actually a OpenSCENARIO2Parser.SumExpressionContext + def __init__(self, parser, ctx: ParserRuleContext): # actually a OpenSCENARIO2Parser.SumExpressionContext super().__init__(parser) self.copyFrom(ctx) def term(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.TermContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.TermContext, 0) - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterTermExp" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterTermExp"): listener.enterTermExp(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitTermExp" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitTermExp"): listener.exitTermExp(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitTermExp" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitTermExp"): return visitor.visitTermExp(self) else: return visitor.visitChildren(self) - class AdditiveExpContext(SumExpressionContext): - def __init__(self, parser, ctx:ParserRuleContext): # actually a OpenSCENARIO2Parser.SumExpressionContext + def __init__(self, parser, ctx: ParserRuleContext): # actually a OpenSCENARIO2Parser.SumExpressionContext super().__init__(parser) self.copyFrom(ctx) def sumExpression(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.SumExpressionContext,0) + return self.getTypedRuleContext(OpenSCENARIO2Parser.SumExpressionContext, 0) def additiveOp(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.AdditiveOpContext,0) + return self.getTypedRuleContext(OpenSCENARIO2Parser.AdditiveOpContext, 0) def term(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.TermContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.TermContext, 0) - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterAdditiveExp" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterAdditiveExp"): listener.enterAdditiveExp(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitAdditiveExp" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitAdditiveExp"): listener.exitAdditiveExp(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitAdditiveExp" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitAdditiveExp"): return visitor.visitAdditiveExp(self) else: return visitor.visitChildren(self) - - - def sumExpression(self, _p:int=0): + def sumExpression(self, _p: int = 0): _parentctx = self._ctx _parentState = self.state localctx = OpenSCENARIO2Parser.SumExpressionContext(self, self._ctx, _parentState) @@ -9764,13 +8998,14 @@ def sumExpression(self, _p:int=0): self._ctx.stop = self._input.LT(-1) self.state = 1150 self._errHandler.sync(self) - _alt = self._interp.adaptivePredict(self._input,108,self._ctx) - while _alt!=2 and _alt!=ATN.INVALID_ALT_NUMBER: - if _alt==1: + _alt = self._interp.adaptivePredict(self._input, 108, self._ctx) + while _alt != 2 and _alt != ATN.INVALID_ALT_NUMBER: + if _alt == 1: if self._parseListeners is not None: self.triggerExitRuleEvent() _prevctx = localctx - localctx = OpenSCENARIO2Parser.AdditiveExpContext(self, OpenSCENARIO2Parser.SumExpressionContext(self, _parentctx, _parentState)) + localctx = OpenSCENARIO2Parser.AdditiveExpContext( + self, OpenSCENARIO2Parser.SumExpressionContext(self, _parentctx, _parentState)) self.pushNewRecursionContext(localctx, _startState, self.RULE_sumExpression) self.state = 1144 if not self.precpred(self._ctx, 1): @@ -9779,10 +9014,10 @@ def sumExpression(self, _p:int=0): self.state = 1145 self.additiveOp() self.state = 1146 - self.term(0) + self.term(0) self.state = 1152 self._errHandler.sync(self) - _alt = self._interp.adaptivePredict(self._input,108,self._ctx) + _alt = self._interp.adaptivePredict(self._input, 108, self._ctx) except RecognitionException as re: localctx.exception = re @@ -9792,45 +9027,40 @@ def sumExpression(self, _p:int=0): self.unrollRecursionContexts(_parentctx) return localctx - class AdditiveOpContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser - def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_additiveOp - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterAdditiveOp" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterAdditiveOp"): listener.enterAdditiveOp(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitAdditiveOp" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitAdditiveOp"): listener.exitAdditiveOp(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitAdditiveOp" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitAdditiveOp"): return visitor.visitAdditiveOp(self) else: return visitor.visitChildren(self) - - - def additiveOp(self): localctx = OpenSCENARIO2Parser.AdditiveOpContext(self, self._ctx, self.state) self.enterRule(localctx, 242, self.RULE_additiveOp) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 1153 _la = self._input.LA(1) - if not(_la==OpenSCENARIO2Parser.T__84 or _la==OpenSCENARIO2Parser.T__85): + if not(_la == OpenSCENARIO2Parser.T__84 or _la == OpenSCENARIO2Parser.T__85): self._errHandler.recoverInline(self) else: self._errHandler.reportMatch(self) @@ -9843,81 +9073,72 @@ def additiveOp(self): self.exitRule() return localctx - class TermContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser - def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_term - - def copyFrom(self, ctx:ParserRuleContext): + def copyFrom(self, ctx: ParserRuleContext): super().copyFrom(ctx) - class MultiplicativeExpContext(TermContext): - def __init__(self, parser, ctx:ParserRuleContext): # actually a OpenSCENARIO2Parser.TermContext + def __init__(self, parser, ctx: ParserRuleContext): # actually a OpenSCENARIO2Parser.TermContext super().__init__(parser) self.copyFrom(ctx) def term(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.TermContext,0) + return self.getTypedRuleContext(OpenSCENARIO2Parser.TermContext, 0) def multiplicativeOp(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.MultiplicativeOpContext,0) + return self.getTypedRuleContext(OpenSCENARIO2Parser.MultiplicativeOpContext, 0) def factor(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.FactorContext,0) + return self.getTypedRuleContext(OpenSCENARIO2Parser.FactorContext, 0) - - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterMultiplicativeExp" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterMultiplicativeExp"): listener.enterMultiplicativeExp(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitMultiplicativeExp" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitMultiplicativeExp"): listener.exitMultiplicativeExp(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitMultiplicativeExp" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitMultiplicativeExp"): return visitor.visitMultiplicativeExp(self) else: return visitor.visitChildren(self) - class FactorExpContext(TermContext): - def __init__(self, parser, ctx:ParserRuleContext): # actually a OpenSCENARIO2Parser.TermContext + def __init__(self, parser, ctx: ParserRuleContext): # actually a OpenSCENARIO2Parser.TermContext super().__init__(parser) self.copyFrom(ctx) def factor(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.FactorContext,0) + return self.getTypedRuleContext(OpenSCENARIO2Parser.FactorContext, 0) - - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterFactorExp" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterFactorExp"): listener.enterFactorExp(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitFactorExp" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitFactorExp"): listener.exitFactorExp(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitFactorExp" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitFactorExp"): return visitor.visitFactorExp(self) else: return visitor.visitChildren(self) - - - def term(self, _p:int=0): + def term(self, _p: int = 0): _parentctx = self._ctx _parentState = self.state localctx = OpenSCENARIO2Parser.TermContext(self, self._ctx, _parentState) @@ -9935,13 +9156,14 @@ def term(self, _p:int=0): self._ctx.stop = self._input.LT(-1) self.state = 1164 self._errHandler.sync(self) - _alt = self._interp.adaptivePredict(self._input,109,self._ctx) - while _alt!=2 and _alt!=ATN.INVALID_ALT_NUMBER: - if _alt==1: + _alt = self._interp.adaptivePredict(self._input, 109, self._ctx) + while _alt != 2 and _alt != ATN.INVALID_ALT_NUMBER: + if _alt == 1: if self._parseListeners is not None: self.triggerExitRuleEvent() _prevctx = localctx - localctx = OpenSCENARIO2Parser.MultiplicativeExpContext(self, OpenSCENARIO2Parser.TermContext(self, _parentctx, _parentState)) + localctx = OpenSCENARIO2Parser.MultiplicativeExpContext( + self, OpenSCENARIO2Parser.TermContext(self, _parentctx, _parentState)) self.pushNewRecursionContext(localctx, _startState, self.RULE_term) self.state = 1158 if not self.precpred(self._ctx, 1): @@ -9950,10 +9172,10 @@ def term(self, _p:int=0): self.state = 1159 self.multiplicativeOp() self.state = 1160 - self.factor() + self.factor() self.state = 1166 self._errHandler.sync(self) - _alt = self._interp.adaptivePredict(self._input,109,self._ctx) + _alt = self._interp.adaptivePredict(self._input, 109, self._ctx) except RecognitionException as re: localctx.exception = re @@ -9963,40 +9185,35 @@ def term(self, _p:int=0): self.unrollRecursionContexts(_parentctx) return localctx - class MultiplicativeOpContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser - def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_multiplicativeOp - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterMultiplicativeOp" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterMultiplicativeOp"): listener.enterMultiplicativeOp(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitMultiplicativeOp" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitMultiplicativeOp"): listener.exitMultiplicativeOp(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitMultiplicativeOp" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitMultiplicativeOp"): return visitor.visitMultiplicativeOp(self) else: return visitor.visitChildren(self) - - - def multiplicativeOp(self): localctx = OpenSCENARIO2Parser.MultiplicativeOpContext(self, self._ctx, self.state) self.enterRule(localctx, 246, self.RULE_multiplicativeOp) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 1167 @@ -10014,42 +9231,36 @@ def multiplicativeOp(self): self.exitRule() return localctx - class FactorContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def postfixExp(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.PostfixExpContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.PostfixExpContext, 0) def factor(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.FactorContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.FactorContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_factor - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterFactor" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterFactor"): listener.enterFactor(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitFactor" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitFactor"): listener.exitFactor(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitFactor" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitFactor"): return visitor.visitFactor(self) else: return visitor.visitChildren(self) - - - def factor(self): localctx = OpenSCENARIO2Parser.FactorContext(self, self._ctx, self.state) @@ -10081,213 +9292,204 @@ def factor(self): self.exitRule() return localctx - class PostfixExpContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser - def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_postfixExp - - def copyFrom(self, ctx:ParserRuleContext): + def copyFrom(self, ctx: ParserRuleContext): super().copyFrom(ctx) - class PrimaryExpressionContext(PostfixExpContext): - def __init__(self, parser, ctx:ParserRuleContext): # actually a OpenSCENARIO2Parser.PostfixExpContext + def __init__(self, parser, ctx: ParserRuleContext): # actually a OpenSCENARIO2Parser.PostfixExpContext super().__init__(parser) self.copyFrom(ctx) def primaryExp(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.PrimaryExpContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.PrimaryExpContext, 0) - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterPrimaryExpression" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterPrimaryExpression"): listener.enterPrimaryExpression(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitPrimaryExpression" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitPrimaryExpression"): listener.exitPrimaryExpression(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitPrimaryExpression" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitPrimaryExpression"): return visitor.visitPrimaryExpression(self) else: return visitor.visitChildren(self) - class CastExpressionContext(PostfixExpContext): - def __init__(self, parser, ctx:ParserRuleContext): # actually a OpenSCENARIO2Parser.PostfixExpContext + def __init__(self, parser, ctx: ParserRuleContext): # actually a OpenSCENARIO2Parser.PostfixExpContext super().__init__(parser) self.copyFrom(ctx) def postfixExp(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.PostfixExpContext,0) + return self.getTypedRuleContext(OpenSCENARIO2Parser.PostfixExpContext, 0) def OPEN_PAREN(self): return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) + def typeDeclarator(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.TypeDeclaratorContext,0) + return self.getTypedRuleContext(OpenSCENARIO2Parser.TypeDeclaratorContext, 0) def CLOSE_PAREN(self): return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterCastExpression" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterCastExpression"): listener.enterCastExpression(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitCastExpression" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitCastExpression"): listener.exitCastExpression(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitCastExpression" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitCastExpression"): return visitor.visitCastExpression(self) else: return visitor.visitChildren(self) - class FunctionApplicationExpressionContext(PostfixExpContext): - def __init__(self, parser, ctx:ParserRuleContext): # actually a OpenSCENARIO2Parser.PostfixExpContext + def __init__(self, parser, ctx: ParserRuleContext): # actually a OpenSCENARIO2Parser.PostfixExpContext super().__init__(parser) self.copyFrom(ctx) def postfixExp(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.PostfixExpContext,0) + return self.getTypedRuleContext(OpenSCENARIO2Parser.PostfixExpContext, 0) def OPEN_PAREN(self): return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) + def CLOSE_PAREN(self): return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) - def argumentList(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ArgumentListContext,0) + def argumentList(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ArgumentListContext, 0) - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterFunctionApplicationExpression" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterFunctionApplicationExpression"): listener.enterFunctionApplicationExpression(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitFunctionApplicationExpression" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitFunctionApplicationExpression"): listener.exitFunctionApplicationExpression(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitFunctionApplicationExpression" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitFunctionApplicationExpression"): return visitor.visitFunctionApplicationExpression(self) else: return visitor.visitChildren(self) - class FieldAccessExpressionContext(PostfixExpContext): - def __init__(self, parser, ctx:ParserRuleContext): # actually a OpenSCENARIO2Parser.PostfixExpContext + def __init__(self, parser, ctx: ParserRuleContext): # actually a OpenSCENARIO2Parser.PostfixExpContext super().__init__(parser) self.copyFrom(ctx) def postfixExp(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.PostfixExpContext,0) + return self.getTypedRuleContext(OpenSCENARIO2Parser.PostfixExpContext, 0) def fieldName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.FieldNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.FieldNameContext, 0) - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterFieldAccessExpression" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterFieldAccessExpression"): listener.enterFieldAccessExpression(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitFieldAccessExpression" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitFieldAccessExpression"): listener.exitFieldAccessExpression(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitFieldAccessExpression" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitFieldAccessExpression"): return visitor.visitFieldAccessExpression(self) else: return visitor.visitChildren(self) - class ElementAccessExpressionContext(PostfixExpContext): - def __init__(self, parser, ctx:ParserRuleContext): # actually a OpenSCENARIO2Parser.PostfixExpContext + def __init__(self, parser, ctx: ParserRuleContext): # actually a OpenSCENARIO2Parser.PostfixExpContext super().__init__(parser) self.copyFrom(ctx) def postfixExp(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.PostfixExpContext,0) + return self.getTypedRuleContext(OpenSCENARIO2Parser.PostfixExpContext, 0) def OPEN_BRACK(self): return self.getToken(OpenSCENARIO2Parser.OPEN_BRACK, 0) + def expression(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext,0) + return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext, 0) def CLOSE_BRACK(self): return self.getToken(OpenSCENARIO2Parser.CLOSE_BRACK, 0) - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterElementAccessExpression" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterElementAccessExpression"): listener.enterElementAccessExpression(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitElementAccessExpression" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitElementAccessExpression"): listener.exitElementAccessExpression(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitElementAccessExpression" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitElementAccessExpression"): return visitor.visitElementAccessExpression(self) else: return visitor.visitChildren(self) - class TypeTestExpressionContext(PostfixExpContext): - def __init__(self, parser, ctx:ParserRuleContext): # actually a OpenSCENARIO2Parser.PostfixExpContext + def __init__(self, parser, ctx: ParserRuleContext): # actually a OpenSCENARIO2Parser.PostfixExpContext super().__init__(parser) self.copyFrom(ctx) def postfixExp(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.PostfixExpContext,0) + return self.getTypedRuleContext(OpenSCENARIO2Parser.PostfixExpContext, 0) def OPEN_PAREN(self): return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) + def typeDeclarator(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.TypeDeclaratorContext,0) + return self.getTypedRuleContext(OpenSCENARIO2Parser.TypeDeclaratorContext, 0) def CLOSE_PAREN(self): return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterTypeTestExpression" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterTypeTestExpression"): listener.enterTypeTestExpression(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitTypeTestExpression" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitTypeTestExpression"): listener.exitTypeTestExpression(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitTypeTestExpression" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitTypeTestExpression"): return visitor.visitTypeTestExpression(self) else: return visitor.visitChildren(self) - - - def postfixExp(self, _p:int=0): + def postfixExp(self, _p: int = 0): _parentctx = self._ctx _parentState = self.state localctx = OpenSCENARIO2Parser.PostfixExpContext(self, self._ctx, _parentState) _prevctx = localctx _startState = 250 self.enterRecursionRule(localctx, 250, self.RULE_postfixExp, _p) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) localctx = OpenSCENARIO2Parser.PrimaryExpressionContext(self, localctx) @@ -10299,17 +9501,18 @@ def postfixExp(self, _p:int=0): self._ctx.stop = self._input.LT(-1) self.state = 1207 self._errHandler.sync(self) - _alt = self._interp.adaptivePredict(self._input,113,self._ctx) - while _alt!=2 and _alt!=ATN.INVALID_ALT_NUMBER: - if _alt==1: + _alt = self._interp.adaptivePredict(self._input, 113, self._ctx) + while _alt != 2 and _alt != ATN.INVALID_ALT_NUMBER: + if _alt == 1: if self._parseListeners is not None: self.triggerExitRuleEvent() _prevctx = localctx self.state = 1205 self._errHandler.sync(self) - la_ = self._interp.adaptivePredict(self._input,112,self._ctx) + la_ = self._interp.adaptivePredict(self._input, 112, self._ctx) if la_ == 1: - localctx = OpenSCENARIO2Parser.CastExpressionContext(self, OpenSCENARIO2Parser.PostfixExpContext(self, _parentctx, _parentState)) + localctx = OpenSCENARIO2Parser.CastExpressionContext( + self, OpenSCENARIO2Parser.PostfixExpContext(self, _parentctx, _parentState)) self.pushNewRecursionContext(localctx, _startState, self.RULE_postfixExp) self.state = 1177 if not self.precpred(self._ctx, 5): @@ -10328,7 +9531,8 @@ def postfixExp(self, _p:int=0): pass elif la_ == 2: - localctx = OpenSCENARIO2Parser.TypeTestExpressionContext(self, OpenSCENARIO2Parser.PostfixExpContext(self, _parentctx, _parentState)) + localctx = OpenSCENARIO2Parser.TypeTestExpressionContext( + self, OpenSCENARIO2Parser.PostfixExpContext(self, _parentctx, _parentState)) self.pushNewRecursionContext(localctx, _startState, self.RULE_postfixExp) self.state = 1184 if not self.precpred(self._ctx, 4): @@ -10347,7 +9551,8 @@ def postfixExp(self, _p:int=0): pass elif la_ == 3: - localctx = OpenSCENARIO2Parser.ElementAccessExpressionContext(self, OpenSCENARIO2Parser.PostfixExpContext(self, _parentctx, _parentState)) + localctx = OpenSCENARIO2Parser.ElementAccessExpressionContext( + self, OpenSCENARIO2Parser.PostfixExpContext(self, _parentctx, _parentState)) self.pushNewRecursionContext(localctx, _startState, self.RULE_postfixExp) self.state = 1191 if not self.precpred(self._ctx, 3): @@ -10362,7 +9567,8 @@ def postfixExp(self, _p:int=0): pass elif la_ == 4: - localctx = OpenSCENARIO2Parser.FunctionApplicationExpressionContext(self, OpenSCENARIO2Parser.PostfixExpContext(self, _parentctx, _parentState)) + localctx = OpenSCENARIO2Parser.FunctionApplicationExpressionContext( + self, OpenSCENARIO2Parser.PostfixExpContext(self, _parentctx, _parentState)) self.pushNewRecursionContext(localctx, _startState, self.RULE_postfixExp) self.state = 1196 if not self.precpred(self._ctx, 2): @@ -10377,13 +9583,13 @@ def postfixExp(self, _p:int=0): self.state = 1198 self.argumentList() - self.state = 1201 self.match(OpenSCENARIO2Parser.CLOSE_PAREN) pass elif la_ == 5: - localctx = OpenSCENARIO2Parser.FieldAccessExpressionContext(self, OpenSCENARIO2Parser.PostfixExpContext(self, _parentctx, _parentState)) + localctx = OpenSCENARIO2Parser.FieldAccessExpressionContext( + self, OpenSCENARIO2Parser.PostfixExpContext(self, _parentctx, _parentState)) self.pushNewRecursionContext(localctx, _startState, self.RULE_postfixExp) self.state = 1202 if not self.precpred(self._ctx, 1): @@ -10395,10 +9601,9 @@ def postfixExp(self, _p:int=0): self.fieldName() pass - self.state = 1209 self._errHandler.sync(self) - _alt = self._interp.adaptivePredict(self._input,113,self._ctx) + _alt = self._interp.adaptivePredict(self._input, 113, self._ctx) except RecognitionException as re: localctx.exception = re @@ -10408,42 +9613,36 @@ def postfixExp(self, _p:int=0): self.unrollRecursionContexts(_parentctx) return localctx - class FieldAccessContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def postfixExp(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.PostfixExpContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.PostfixExpContext, 0) def fieldName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.FieldNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.FieldNameContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_fieldAccess - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterFieldAccess" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterFieldAccess"): listener.enterFieldAccess(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitFieldAccess" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitFieldAccess"): listener.exitFieldAccess(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitFieldAccess" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitFieldAccess"): return visitor.visitFieldAccess(self) else: return visitor.visitChildren(self) - - - def fieldAccess(self): localctx = OpenSCENARIO2Parser.FieldAccessContext(self, self._ctx, self.state) @@ -10464,17 +9663,15 @@ def fieldAccess(self): self.exitRule() return localctx - class PrimaryExpContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def valueExp(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ValueExpContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ValueExpContext, 0) def Identifier(self): return self.getToken(OpenSCENARIO2Parser.Identifier, 0) @@ -10483,8 +9680,7 @@ def OPEN_PAREN(self): return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) def expression(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext, 0) def CLOSE_PAREN(self): return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) @@ -10492,23 +9688,20 @@ def CLOSE_PAREN(self): def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_primaryExp - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterPrimaryExp" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterPrimaryExp"): listener.enterPrimaryExp(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitPrimaryExp" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitPrimaryExp"): listener.exitPrimaryExp(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitPrimaryExp" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitPrimaryExp"): return visitor.visitPrimaryExp(self) else: return visitor.visitChildren(self) - - - def primaryExp(self): localctx = OpenSCENARIO2Parser.PrimaryExpContext(self, self._ctx, self.state) @@ -10516,7 +9709,7 @@ def primaryExp(self): try: self.state = 1221 self._errHandler.sync(self) - la_ = self._interp.adaptivePredict(self._input,114,self._ctx) + la_ = self._interp.adaptivePredict(self._input, 114, self._ctx) if la_ == 1: self.enterOuterAlt(localctx, 1) self.state = 1214 @@ -10545,7 +9738,6 @@ def primaryExp(self): self.match(OpenSCENARIO2Parser.CLOSE_PAREN) pass - except RecognitionException as re: localctx.exception = re self._errHandler.reportError(self, re) @@ -10554,24 +9746,21 @@ def primaryExp(self): self.exitRule() return localctx - class ValueExpContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def physicalLiteral(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.PhysicalLiteralContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.PhysicalLiteralContext, 0) def FloatLiteral(self): return self.getToken(OpenSCENARIO2Parser.FloatLiteral, 0) def integerLiteral(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.IntegerLiteralContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.IntegerLiteralContext, 0) def BoolLiteral(self): return self.getToken(OpenSCENARIO2Parser.BoolLiteral, 0) @@ -10580,41 +9769,34 @@ def StringLiteral(self): return self.getToken(OpenSCENARIO2Parser.StringLiteral, 0) def identifierReference(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.IdentifierReferenceContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.IdentifierReferenceContext, 0) def enumValueReference(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.EnumValueReferenceContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.EnumValueReferenceContext, 0) def listConstructor(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ListConstructorContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ListConstructorContext, 0) def rangeConstructor(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.RangeConstructorContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.RangeConstructorContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_valueExp - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterValueExp" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterValueExp"): listener.enterValueExp(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitValueExp" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitValueExp"): listener.exitValueExp(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitValueExp" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitValueExp"): return visitor.visitValueExp(self) else: return visitor.visitChildren(self) - - - def valueExp(self): localctx = OpenSCENARIO2Parser.ValueExpContext(self, self._ctx, self.state) @@ -10622,7 +9804,7 @@ def valueExp(self): try: self.state = 1232 self._errHandler.sync(self) - la_ = self._interp.adaptivePredict(self._input,115,self._ctx) + la_ = self._interp.adaptivePredict(self._input, 115, self._ctx) if la_ == 1: self.enterOuterAlt(localctx, 1) self.state = 1223 @@ -10677,7 +9859,6 @@ def valueExp(self): self.rangeConstructor() pass - except RecognitionException as re: localctx.exception = re self._errHandler.reportError(self, re) @@ -10686,23 +9867,21 @@ def valueExp(self): self.exitRule() return localctx - class ListConstructorContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def OPEN_BRACK(self): return self.getToken(OpenSCENARIO2Parser.OPEN_BRACK, 0) - def expression(self, i:int=None): + def expression(self, i: int = None): if i is None: return self.getTypedRuleContexts(OpenSCENARIO2Parser.ExpressionContext) else: - return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext,i) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext, i) def CLOSE_BRACK(self): return self.getToken(OpenSCENARIO2Parser.CLOSE_BRACK, 0) @@ -10710,28 +9889,25 @@ def CLOSE_BRACK(self): def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_listConstructor - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterListConstructor" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterListConstructor"): listener.enterListConstructor(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitListConstructor" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitListConstructor"): listener.exitListConstructor(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitListConstructor" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitListConstructor"): return visitor.visitListConstructor(self) else: return visitor.visitChildren(self) - - - def listConstructor(self): localctx = OpenSCENARIO2Parser.ListConstructorContext(self, self._ctx, self.state) self.enterRule(localctx, 258, self.RULE_listConstructor) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 1234 @@ -10741,7 +9917,7 @@ def listConstructor(self): self.state = 1240 self._errHandler.sync(self) _la = self._input.LA(1) - while _la==OpenSCENARIO2Parser.T__7: + while _la == OpenSCENARIO2Parser.T__7: self.state = 1236 self.match(OpenSCENARIO2Parser.T__7) self.state = 1237 @@ -10760,23 +9936,21 @@ def listConstructor(self): self.exitRule() return localctx - class RangeConstructorContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def OPEN_PAREN(self): return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) - def expression(self, i:int=None): + def expression(self, i: int = None): if i is None: return self.getTypedRuleContexts(OpenSCENARIO2Parser.ExpressionContext) else: - return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext,i) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext, i) def CLOSE_PAREN(self): return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) @@ -10790,23 +9964,20 @@ def CLOSE_BRACK(self): def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_rangeConstructor - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterRangeConstructor" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterRangeConstructor"): listener.enterRangeConstructor(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitRangeConstructor" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitRangeConstructor"): listener.exitRangeConstructor(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitRangeConstructor" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitRangeConstructor"): return visitor.visitRangeConstructor(self) else: return visitor.visitChildren(self) - - - def rangeConstructor(self): localctx = OpenSCENARIO2Parser.RangeConstructorContext(self, self._ctx, self.state) @@ -10854,41 +10025,36 @@ def rangeConstructor(self): self.exitRule() return localctx - class IdentifierReferenceContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser - def fieldName(self, i:int=None): + def fieldName(self, i: int = None): if i is None: return self.getTypedRuleContexts(OpenSCENARIO2Parser.FieldNameContext) else: - return self.getTypedRuleContext(OpenSCENARIO2Parser.FieldNameContext,i) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.FieldNameContext, i) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_identifierReference - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterIdentifierReference" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterIdentifierReference"): listener.enterIdentifierReference(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitIdentifierReference" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitIdentifierReference"): listener.exitIdentifierReference(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitIdentifierReference" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitIdentifierReference"): return visitor.visitIdentifierReference(self) else: return visitor.visitChildren(self) - - - def identifierReference(self): localctx = OpenSCENARIO2Parser.IdentifierReferenceContext(self, self._ctx, self.state) @@ -10897,16 +10063,16 @@ def identifierReference(self): self.enterOuterAlt(localctx, 1) self.state = 1265 self._errHandler.sync(self) - _alt = self._interp.adaptivePredict(self._input,118,self._ctx) - while _alt!=2 and _alt!=ATN.INVALID_ALT_NUMBER: - if _alt==1: + _alt = self._interp.adaptivePredict(self._input, 118, self._ctx) + while _alt != 2 and _alt != ATN.INVALID_ALT_NUMBER: + if _alt == 1: self.state = 1260 self.fieldName() self.state = 1261 - self.match(OpenSCENARIO2Parser.T__1) + self.match(OpenSCENARIO2Parser.T__1) self.state = 1267 self._errHandler.sync(self) - _alt = self._interp.adaptivePredict(self._input,118,self._ctx) + _alt = self._interp.adaptivePredict(self._input, 118, self._ctx) self.state = 1268 self.fieldName() @@ -10918,46 +10084,41 @@ def identifierReference(self): self.exitRule() return localctx - class ArgumentListSpecificationContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser - def argumentSpecification(self, i:int=None): + def argumentSpecification(self, i: int = None): if i is None: return self.getTypedRuleContexts(OpenSCENARIO2Parser.ArgumentSpecificationContext) else: - return self.getTypedRuleContext(OpenSCENARIO2Parser.ArgumentSpecificationContext,i) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ArgumentSpecificationContext, i) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_argumentListSpecification - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterArgumentListSpecification" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterArgumentListSpecification"): listener.enterArgumentListSpecification(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitArgumentListSpecification" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitArgumentListSpecification"): listener.exitArgumentListSpecification(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitArgumentListSpecification" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitArgumentListSpecification"): return visitor.visitArgumentListSpecification(self) else: return visitor.visitChildren(self) - - - def argumentListSpecification(self): localctx = OpenSCENARIO2Parser.ArgumentListSpecificationContext(self, self._ctx, self.state) self.enterRule(localctx, 264, self.RULE_argumentListSpecification) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 1270 @@ -10965,7 +10126,7 @@ def argumentListSpecification(self): self.state = 1275 self._errHandler.sync(self) _la = self._input.LA(1) - while _la==OpenSCENARIO2Parser.T__7: + while _la == OpenSCENARIO2Parser.T__7: self.state = 1271 self.match(OpenSCENARIO2Parser.T__7) self.state = 1272 @@ -10982,51 +10143,44 @@ def argumentListSpecification(self): self.exitRule() return localctx - class ArgumentSpecificationContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def argumentName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ArgumentNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ArgumentNameContext, 0) def typeDeclarator(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.TypeDeclaratorContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.TypeDeclaratorContext, 0) def defaultValue(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.DefaultValueContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.DefaultValueContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_argumentSpecification - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterArgumentSpecification" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterArgumentSpecification"): listener.enterArgumentSpecification(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitArgumentSpecification" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitArgumentSpecification"): listener.exitArgumentSpecification(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitArgumentSpecification" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitArgumentSpecification"): return visitor.visitArgumentSpecification(self) else: return visitor.visitChildren(self) - - - def argumentSpecification(self): localctx = OpenSCENARIO2Parser.ArgumentSpecificationContext(self, self._ctx, self.state) self.enterRule(localctx, 266, self.RULE_argumentSpecification) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 1278 @@ -11038,13 +10192,12 @@ def argumentSpecification(self): self.state = 1283 self._errHandler.sync(self) _la = self._input.LA(1) - if _la==OpenSCENARIO2Parser.T__20: + if _la == OpenSCENARIO2Parser.T__20: self.state = 1281 self.match(OpenSCENARIO2Parser.T__20) self.state = 1282 self.defaultValue() - except RecognitionException as re: localctx.exception = re self._errHandler.reportError(self, re) @@ -11053,11 +10206,10 @@ def argumentSpecification(self): self.exitRule() return localctx - class ArgumentNameContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser @@ -11067,23 +10219,20 @@ def Identifier(self): def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_argumentName - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterArgumentName" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterArgumentName"): listener.enterArgumentName(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitArgumentName" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitArgumentName"): listener.exitArgumentName(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitArgumentName" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitArgumentName"): return visitor.visitArgumentName(self) else: return visitor.visitChildren(self) - - - def argumentName(self): localctx = OpenSCENARIO2Parser.ArgumentNameContext(self, self._ctx, self.state) @@ -11100,78 +10249,72 @@ def argumentName(self): self.exitRule() return localctx - class ArgumentListContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser - def positionalArgument(self, i:int=None): + def positionalArgument(self, i: int = None): if i is None: return self.getTypedRuleContexts(OpenSCENARIO2Parser.PositionalArgumentContext) else: - return self.getTypedRuleContext(OpenSCENARIO2Parser.PositionalArgumentContext,i) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.PositionalArgumentContext, i) - def namedArgument(self, i:int=None): + def namedArgument(self, i: int = None): if i is None: return self.getTypedRuleContexts(OpenSCENARIO2Parser.NamedArgumentContext) else: - return self.getTypedRuleContext(OpenSCENARIO2Parser.NamedArgumentContext,i) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.NamedArgumentContext, i) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_argumentList - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterArgumentList" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterArgumentList"): listener.enterArgumentList(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitArgumentList" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitArgumentList"): listener.exitArgumentList(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitArgumentList" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitArgumentList"): return visitor.visitArgumentList(self) else: return visitor.visitChildren(self) - - - def argumentList(self): localctx = OpenSCENARIO2Parser.ArgumentListContext(self, self._ctx, self.state) self.enterRule(localctx, 270, self.RULE_argumentList) - self._la = 0 # Token type + self._la = 0 # Token type try: self.state = 1310 self._errHandler.sync(self) - la_ = self._interp.adaptivePredict(self._input,124,self._ctx) + la_ = self._interp.adaptivePredict(self._input, 124, self._ctx) if la_ == 1: self.enterOuterAlt(localctx, 1) self.state = 1287 self.positionalArgument() self.state = 1292 self._errHandler.sync(self) - _alt = self._interp.adaptivePredict(self._input,121,self._ctx) - while _alt!=2 and _alt!=ATN.INVALID_ALT_NUMBER: - if _alt==1: + _alt = self._interp.adaptivePredict(self._input, 121, self._ctx) + while _alt != 2 and _alt != ATN.INVALID_ALT_NUMBER: + if _alt == 1: self.state = 1288 self.match(OpenSCENARIO2Parser.T__7) self.state = 1289 - self.positionalArgument() + self.positionalArgument() self.state = 1294 self._errHandler.sync(self) - _alt = self._interp.adaptivePredict(self._input,121,self._ctx) + _alt = self._interp.adaptivePredict(self._input, 121, self._ctx) self.state = 1299 self._errHandler.sync(self) _la = self._input.LA(1) - while _la==OpenSCENARIO2Parser.T__7: + while _la == OpenSCENARIO2Parser.T__7: self.state = 1295 self.match(OpenSCENARIO2Parser.T__7) self.state = 1296 @@ -11189,7 +10332,7 @@ def argumentList(self): self.state = 1307 self._errHandler.sync(self) _la = self._input.LA(1) - while _la==OpenSCENARIO2Parser.T__7: + while _la == OpenSCENARIO2Parser.T__7: self.state = 1303 self.match(OpenSCENARIO2Parser.T__7) self.state = 1304 @@ -11200,7 +10343,6 @@ def argumentList(self): pass - except RecognitionException as re: localctx.exception = re self._errHandler.reportError(self, re) @@ -11209,38 +10351,33 @@ def argumentList(self): self.exitRule() return localctx - class PositionalArgumentContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def expression(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_positionalArgument - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterPositionalArgument" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterPositionalArgument"): listener.enterPositionalArgument(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitPositionalArgument" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitPositionalArgument"): listener.exitPositionalArgument(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitPositionalArgument" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitPositionalArgument"): return visitor.visitPositionalArgument(self) else: return visitor.visitChildren(self) - - - def positionalArgument(self): localctx = OpenSCENARIO2Parser.PositionalArgumentContext(self, self._ctx, self.state) @@ -11257,42 +10394,36 @@ def positionalArgument(self): self.exitRule() return localctx - class NamedArgumentContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def argumentName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ArgumentNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ArgumentNameContext, 0) def expression(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_namedArgument - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterNamedArgument" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterNamedArgument"): listener.enterNamedArgument(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitNamedArgument" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitNamedArgument"): listener.exitNamedArgument(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitNamedArgument" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitNamedArgument"): return visitor.visitNamedArgument(self) else: return visitor.visitChildren(self) - - - def namedArgument(self): localctx = OpenSCENARIO2Parser.NamedArgumentContext(self, self._ctx, self.state) @@ -11313,45 +10444,39 @@ def namedArgument(self): self.exitRule() return localctx - class PhysicalLiteralContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser def unitName(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.UnitNameContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.UnitNameContext, 0) def FloatLiteral(self): return self.getToken(OpenSCENARIO2Parser.FloatLiteral, 0) def integerLiteral(self): - return self.getTypedRuleContext(OpenSCENARIO2Parser.IntegerLiteralContext,0) - + return self.getTypedRuleContext(OpenSCENARIO2Parser.IntegerLiteralContext, 0) def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_physicalLiteral - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterPhysicalLiteral" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterPhysicalLiteral"): listener.enterPhysicalLiteral(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitPhysicalLiteral" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitPhysicalLiteral"): listener.exitPhysicalLiteral(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitPhysicalLiteral" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitPhysicalLiteral"): return visitor.visitPhysicalLiteral(self) else: return visitor.visitChildren(self) - - - def physicalLiteral(self): localctx = OpenSCENARIO2Parser.PhysicalLiteralContext(self, self._ctx, self.state) @@ -11382,11 +10507,10 @@ def physicalLiteral(self): self.exitRule() return localctx - class IntegerLiteralContext(ParserRuleContext): __slots__ = 'parser' - def __init__(self, parser, parent:ParserRuleContext=None, invokingState:int=-1): + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): super().__init__(parent, invokingState) self.parser = parser @@ -11402,28 +10526,25 @@ def IntLiteral(self): def getRuleIndex(self): return OpenSCENARIO2Parser.RULE_integerLiteral - def enterRule(self, listener:ParseTreeListener): - if hasattr( listener, "enterIntegerLiteral" ): + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterIntegerLiteral"): listener.enterIntegerLiteral(self) - def exitRule(self, listener:ParseTreeListener): - if hasattr( listener, "exitIntegerLiteral" ): + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitIntegerLiteral"): listener.exitIntegerLiteral(self) - def accept(self, visitor:ParseTreeVisitor): - if hasattr( visitor, "visitIntegerLiteral" ): + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitIntegerLiteral"): return visitor.visitIntegerLiteral(self) else: return visitor.visitChildren(self) - - - def integerLiteral(self): localctx = OpenSCENARIO2Parser.IntegerLiteralContext(self, self._ctx, self.state) self.enterRule(localctx, 278, self.RULE_integerLiteral) - self._la = 0 # Token type + self._la = 0 # Token type try: self.enterOuterAlt(localctx, 1) self.state = 1324 @@ -11441,9 +10562,7 @@ def integerLiteral(self): self.exitRule() return localctx - - - def sempred(self, localctx:RuleContext, ruleIndex:int, predIndex:int): + def sempred(self, localctx: RuleContext, ruleIndex: int, predIndex: int): if self._predicates == None: self._predicates = dict() self._predicates[4] = self.structuredIdentifier_sempred @@ -11457,47 +10576,34 @@ def sempred(self, localctx:RuleContext, ruleIndex:int, predIndex:int): else: return pred(localctx, predIndex) - def structuredIdentifier_sempred(self, localctx:StructuredIdentifierContext, predIndex:int): - if predIndex == 0: - return self.precpred(self._ctx, 1) - - - def relation_sempred(self, localctx:RelationContext, predIndex:int): - if predIndex == 1: - return self.precpred(self._ctx, 1) - - - def sumExpression_sempred(self, localctx:SumExpressionContext, predIndex:int): - if predIndex == 2: - return self.precpred(self._ctx, 1) - - - def term_sempred(self, localctx:TermContext, predIndex:int): - if predIndex == 3: - return self.precpred(self._ctx, 1) - - - def postfixExp_sempred(self, localctx:PostfixExpContext, predIndex:int): - if predIndex == 4: - return self.precpred(self._ctx, 5) - + def structuredIdentifier_sempred(self, localctx: StructuredIdentifierContext, predIndex: int): + if predIndex == 0: + return self.precpred(self._ctx, 1) - if predIndex == 5: - return self.precpred(self._ctx, 4) - + def relation_sempred(self, localctx: RelationContext, predIndex: int): + if predIndex == 1: + return self.precpred(self._ctx, 1) - if predIndex == 6: - return self.precpred(self._ctx, 3) - + def sumExpression_sempred(self, localctx: SumExpressionContext, predIndex: int): + if predIndex == 2: + return self.precpred(self._ctx, 1) - if predIndex == 7: - return self.precpred(self._ctx, 2) - + def term_sempred(self, localctx: TermContext, predIndex: int): + if predIndex == 3: + return self.precpred(self._ctx, 1) - if predIndex == 8: - return self.precpred(self._ctx, 1) - + def postfixExp_sempred(self, localctx: PostfixExpContext, predIndex: int): + if predIndex == 4: + return self.precpred(self._ctx, 5) + if predIndex == 5: + return self.precpred(self._ctx, 4) + if predIndex == 6: + return self.precpred(self._ctx, 3) + if predIndex == 7: + return self.precpred(self._ctx, 2) + if predIndex == 8: + return self.precpred(self._ctx, 1) diff --git a/scenario_execution/scenario_execution/osc2_parsing/OpenSCENARIO2Visitor.py b/scenario_execution/scenario_execution/osc2_parsing/OpenSCENARIO2Visitor.py index a0d2cc09..f0101914 100644 --- a/scenario_execution/scenario_execution/osc2_parsing/OpenSCENARIO2Visitor.py +++ b/scenario_execution/scenario_execution/osc2_parsing/OpenSCENARIO2Visitor.py @@ -1,3 +1,19 @@ +# Copyright (C) 2024 Intel Corporation +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, +# software distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions +# and limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + # Generated from OpenSCENARIO2.g4 by ANTLR 4.9.1 from antlr4 import * if __name__ is not None and "." in __name__: @@ -7,772 +23,620 @@ # This class defines a complete generic visitor for a parse tree produced by OpenSCENARIO2Parser. + class OpenSCENARIO2Visitor(ParseTreeVisitor): # Visit a parse tree produced by OpenSCENARIO2Parser#osc_file. - def visitOsc_file(self, ctx:OpenSCENARIO2Parser.Osc_fileContext): + def visitOsc_file(self, ctx: OpenSCENARIO2Parser.Osc_fileContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#preludeStatement. - def visitPreludeStatement(self, ctx:OpenSCENARIO2Parser.PreludeStatementContext): + def visitPreludeStatement(self, ctx: OpenSCENARIO2Parser.PreludeStatementContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#importStatement. - def visitImportStatement(self, ctx:OpenSCENARIO2Parser.ImportStatementContext): + def visitImportStatement(self, ctx: OpenSCENARIO2Parser.ImportStatementContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#importReference. - def visitImportReference(self, ctx:OpenSCENARIO2Parser.ImportReferenceContext): + def visitImportReference(self, ctx: OpenSCENARIO2Parser.ImportReferenceContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#structuredIdentifier. - def visitStructuredIdentifier(self, ctx:OpenSCENARIO2Parser.StructuredIdentifierContext): + def visitStructuredIdentifier(self, ctx: OpenSCENARIO2Parser.StructuredIdentifierContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#oscDeclaration. - def visitOscDeclaration(self, ctx:OpenSCENARIO2Parser.OscDeclarationContext): + def visitOscDeclaration(self, ctx: OpenSCENARIO2Parser.OscDeclarationContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#physicalTypeDeclaration. - def visitPhysicalTypeDeclaration(self, ctx:OpenSCENARIO2Parser.PhysicalTypeDeclarationContext): + def visitPhysicalTypeDeclaration(self, ctx: OpenSCENARIO2Parser.PhysicalTypeDeclarationContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#physicalTypeName. - def visitPhysicalTypeName(self, ctx:OpenSCENARIO2Parser.PhysicalTypeNameContext): + def visitPhysicalTypeName(self, ctx: OpenSCENARIO2Parser.PhysicalTypeNameContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#baseUnitSpecifier. - def visitBaseUnitSpecifier(self, ctx:OpenSCENARIO2Parser.BaseUnitSpecifierContext): + def visitBaseUnitSpecifier(self, ctx: OpenSCENARIO2Parser.BaseUnitSpecifierContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#sIBaseUnitSpecifier. - def visitSIBaseUnitSpecifier(self, ctx:OpenSCENARIO2Parser.SIBaseUnitSpecifierContext): + def visitSIBaseUnitSpecifier(self, ctx: OpenSCENARIO2Parser.SIBaseUnitSpecifierContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#unitDeclaration. - def visitUnitDeclaration(self, ctx:OpenSCENARIO2Parser.UnitDeclarationContext): + def visitUnitDeclaration(self, ctx: OpenSCENARIO2Parser.UnitDeclarationContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#unitSpecifier. - def visitUnitSpecifier(self, ctx:OpenSCENARIO2Parser.UnitSpecifierContext): + def visitUnitSpecifier(self, ctx: OpenSCENARIO2Parser.UnitSpecifierContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#unitName. - def visitUnitName(self, ctx:OpenSCENARIO2Parser.UnitNameContext): + def visitUnitName(self, ctx: OpenSCENARIO2Parser.UnitNameContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#siBaseExponentList. - def visitSiBaseExponentList(self, ctx:OpenSCENARIO2Parser.SiBaseExponentListContext): + def visitSiBaseExponentList(self, ctx: OpenSCENARIO2Parser.SiBaseExponentListContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#siBaseExponent. - def visitSiBaseExponent(self, ctx:OpenSCENARIO2Parser.SiBaseExponentContext): + def visitSiBaseExponent(self, ctx: OpenSCENARIO2Parser.SiBaseExponentContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#siUnitSpecifier. - def visitSiUnitSpecifier(self, ctx:OpenSCENARIO2Parser.SiUnitSpecifierContext): + def visitSiUnitSpecifier(self, ctx: OpenSCENARIO2Parser.SiUnitSpecifierContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#siFactor. - def visitSiFactor(self, ctx:OpenSCENARIO2Parser.SiFactorContext): + def visitSiFactor(self, ctx: OpenSCENARIO2Parser.SiFactorContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#siOffset. - def visitSiOffset(self, ctx:OpenSCENARIO2Parser.SiOffsetContext): + def visitSiOffset(self, ctx: OpenSCENARIO2Parser.SiOffsetContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#siBaseUnitName. - def visitSiBaseUnitName(self, ctx:OpenSCENARIO2Parser.SiBaseUnitNameContext): + def visitSiBaseUnitName(self, ctx: OpenSCENARIO2Parser.SiBaseUnitNameContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#enumDeclaration. - def visitEnumDeclaration(self, ctx:OpenSCENARIO2Parser.EnumDeclarationContext): + def visitEnumDeclaration(self, ctx: OpenSCENARIO2Parser.EnumDeclarationContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#enumMemberDecl. - def visitEnumMemberDecl(self, ctx:OpenSCENARIO2Parser.EnumMemberDeclContext): + def visitEnumMemberDecl(self, ctx: OpenSCENARIO2Parser.EnumMemberDeclContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#enumMemberValue. - def visitEnumMemberValue(self, ctx:OpenSCENARIO2Parser.EnumMemberValueContext): + def visitEnumMemberValue(self, ctx: OpenSCENARIO2Parser.EnumMemberValueContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#enumName. - def visitEnumName(self, ctx:OpenSCENARIO2Parser.EnumNameContext): + def visitEnumName(self, ctx: OpenSCENARIO2Parser.EnumNameContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#enumMemberName. - def visitEnumMemberName(self, ctx:OpenSCENARIO2Parser.EnumMemberNameContext): + def visitEnumMemberName(self, ctx: OpenSCENARIO2Parser.EnumMemberNameContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#enumValueReference. - def visitEnumValueReference(self, ctx:OpenSCENARIO2Parser.EnumValueReferenceContext): + def visitEnumValueReference(self, ctx: OpenSCENARIO2Parser.EnumValueReferenceContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#inheritsCondition. - def visitInheritsCondition(self, ctx:OpenSCENARIO2Parser.InheritsConditionContext): + def visitInheritsCondition(self, ctx: OpenSCENARIO2Parser.InheritsConditionContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#structDeclaration. - def visitStructDeclaration(self, ctx:OpenSCENARIO2Parser.StructDeclarationContext): + def visitStructDeclaration(self, ctx: OpenSCENARIO2Parser.StructDeclarationContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#structInherits. - def visitStructInherits(self, ctx:OpenSCENARIO2Parser.StructInheritsContext): + def visitStructInherits(self, ctx: OpenSCENARIO2Parser.StructInheritsContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#structMemberDecl. - def visitStructMemberDecl(self, ctx:OpenSCENARIO2Parser.StructMemberDeclContext): + def visitStructMemberDecl(self, ctx: OpenSCENARIO2Parser.StructMemberDeclContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#fieldName. - def visitFieldName(self, ctx:OpenSCENARIO2Parser.FieldNameContext): + def visitFieldName(self, ctx: OpenSCENARIO2Parser.FieldNameContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#structName. - def visitStructName(self, ctx:OpenSCENARIO2Parser.StructNameContext): + def visitStructName(self, ctx: OpenSCENARIO2Parser.StructNameContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#actorDeclaration. - def visitActorDeclaration(self, ctx:OpenSCENARIO2Parser.ActorDeclarationContext): + def visitActorDeclaration(self, ctx: OpenSCENARIO2Parser.ActorDeclarationContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#actorInherits. - def visitActorInherits(self, ctx:OpenSCENARIO2Parser.ActorInheritsContext): + def visitActorInherits(self, ctx: OpenSCENARIO2Parser.ActorInheritsContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#actorMemberDecl. - def visitActorMemberDecl(self, ctx:OpenSCENARIO2Parser.ActorMemberDeclContext): + def visitActorMemberDecl(self, ctx: OpenSCENARIO2Parser.ActorMemberDeclContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#actorName. - def visitActorName(self, ctx:OpenSCENARIO2Parser.ActorNameContext): + def visitActorName(self, ctx: OpenSCENARIO2Parser.ActorNameContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#scenarioDeclaration. - def visitScenarioDeclaration(self, ctx:OpenSCENARIO2Parser.ScenarioDeclarationContext): + def visitScenarioDeclaration(self, ctx: OpenSCENARIO2Parser.ScenarioDeclarationContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#scenarioInherits. - def visitScenarioInherits(self, ctx:OpenSCENARIO2Parser.ScenarioInheritsContext): + def visitScenarioInherits(self, ctx: OpenSCENARIO2Parser.ScenarioInheritsContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#scenarioMemberDecl. - def visitScenarioMemberDecl(self, ctx:OpenSCENARIO2Parser.ScenarioMemberDeclContext): + def visitScenarioMemberDecl(self, ctx: OpenSCENARIO2Parser.ScenarioMemberDeclContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#qualifiedBehaviorName. - def visitQualifiedBehaviorName(self, ctx:OpenSCENARIO2Parser.QualifiedBehaviorNameContext): + def visitQualifiedBehaviorName(self, ctx: OpenSCENARIO2Parser.QualifiedBehaviorNameContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#behaviorName. - def visitBehaviorName(self, ctx:OpenSCENARIO2Parser.BehaviorNameContext): + def visitBehaviorName(self, ctx: OpenSCENARIO2Parser.BehaviorNameContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#actionDeclaration. - def visitActionDeclaration(self, ctx:OpenSCENARIO2Parser.ActionDeclarationContext): + def visitActionDeclaration(self, ctx: OpenSCENARIO2Parser.ActionDeclarationContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#actionInherits. - def visitActionInherits(self, ctx:OpenSCENARIO2Parser.ActionInheritsContext): + def visitActionInherits(self, ctx: OpenSCENARIO2Parser.ActionInheritsContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#modifierDeclaration. - def visitModifierDeclaration(self, ctx:OpenSCENARIO2Parser.ModifierDeclarationContext): + def visitModifierDeclaration(self, ctx: OpenSCENARIO2Parser.ModifierDeclarationContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#modifierName. - def visitModifierName(self, ctx:OpenSCENARIO2Parser.ModifierNameContext): + def visitModifierName(self, ctx: OpenSCENARIO2Parser.ModifierNameContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#typeExtension. - def visitTypeExtension(self, ctx:OpenSCENARIO2Parser.TypeExtensionContext): + def visitTypeExtension(self, ctx: OpenSCENARIO2Parser.TypeExtensionContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#enumTypeExtension. - def visitEnumTypeExtension(self, ctx:OpenSCENARIO2Parser.EnumTypeExtensionContext): + def visitEnumTypeExtension(self, ctx: OpenSCENARIO2Parser.EnumTypeExtensionContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#structuredTypeExtension. - def visitStructuredTypeExtension(self, ctx:OpenSCENARIO2Parser.StructuredTypeExtensionContext): + def visitStructuredTypeExtension(self, ctx: OpenSCENARIO2Parser.StructuredTypeExtensionContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#extendableTypeName. - def visitExtendableTypeName(self, ctx:OpenSCENARIO2Parser.ExtendableTypeNameContext): + def visitExtendableTypeName(self, ctx: OpenSCENARIO2Parser.ExtendableTypeNameContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#extensionMemberDecl. - def visitExtensionMemberDecl(self, ctx:OpenSCENARIO2Parser.ExtensionMemberDeclContext): + def visitExtensionMemberDecl(self, ctx: OpenSCENARIO2Parser.ExtensionMemberDeclContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#globalParameterDeclaration. - def visitGlobalParameterDeclaration(self, ctx:OpenSCENARIO2Parser.GlobalParameterDeclarationContext): + def visitGlobalParameterDeclaration(self, ctx: OpenSCENARIO2Parser.GlobalParameterDeclarationContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#typeDeclarator. - def visitTypeDeclarator(self, ctx:OpenSCENARIO2Parser.TypeDeclaratorContext): + def visitTypeDeclarator(self, ctx: OpenSCENARIO2Parser.TypeDeclaratorContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#nonAggregateTypeDeclarator. - def visitNonAggregateTypeDeclarator(self, ctx:OpenSCENARIO2Parser.NonAggregateTypeDeclaratorContext): + def visitNonAggregateTypeDeclarator(self, ctx: OpenSCENARIO2Parser.NonAggregateTypeDeclaratorContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#aggregateTypeDeclarator. - def visitAggregateTypeDeclarator(self, ctx:OpenSCENARIO2Parser.AggregateTypeDeclaratorContext): + def visitAggregateTypeDeclarator(self, ctx: OpenSCENARIO2Parser.AggregateTypeDeclaratorContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#listTypeDeclarator. - def visitListTypeDeclarator(self, ctx:OpenSCENARIO2Parser.ListTypeDeclaratorContext): + def visitListTypeDeclarator(self, ctx: OpenSCENARIO2Parser.ListTypeDeclaratorContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#primitiveType. - def visitPrimitiveType(self, ctx:OpenSCENARIO2Parser.PrimitiveTypeContext): + def visitPrimitiveType(self, ctx: OpenSCENARIO2Parser.PrimitiveTypeContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#typeName. - def visitTypeName(self, ctx:OpenSCENARIO2Parser.TypeNameContext): + def visitTypeName(self, ctx: OpenSCENARIO2Parser.TypeNameContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#eventDeclaration. - def visitEventDeclaration(self, ctx:OpenSCENARIO2Parser.EventDeclarationContext): + def visitEventDeclaration(self, ctx: OpenSCENARIO2Parser.EventDeclarationContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#eventSpecification. - def visitEventSpecification(self, ctx:OpenSCENARIO2Parser.EventSpecificationContext): + def visitEventSpecification(self, ctx: OpenSCENARIO2Parser.EventSpecificationContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#eventReference. - def visitEventReference(self, ctx:OpenSCENARIO2Parser.EventReferenceContext): + def visitEventReference(self, ctx: OpenSCENARIO2Parser.EventReferenceContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#eventFieldDecl. - def visitEventFieldDecl(self, ctx:OpenSCENARIO2Parser.EventFieldDeclContext): + def visitEventFieldDecl(self, ctx: OpenSCENARIO2Parser.EventFieldDeclContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#eventFieldName. - def visitEventFieldName(self, ctx:OpenSCENARIO2Parser.EventFieldNameContext): + def visitEventFieldName(self, ctx: OpenSCENARIO2Parser.EventFieldNameContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#eventName. - def visitEventName(self, ctx:OpenSCENARIO2Parser.EventNameContext): + def visitEventName(self, ctx: OpenSCENARIO2Parser.EventNameContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#eventPath. - def visitEventPath(self, ctx:OpenSCENARIO2Parser.EventPathContext): + def visitEventPath(self, ctx: OpenSCENARIO2Parser.EventPathContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#eventCondition. - def visitEventCondition(self, ctx:OpenSCENARIO2Parser.EventConditionContext): + def visitEventCondition(self, ctx: OpenSCENARIO2Parser.EventConditionContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#riseExpression. - def visitRiseExpression(self, ctx:OpenSCENARIO2Parser.RiseExpressionContext): + def visitRiseExpression(self, ctx: OpenSCENARIO2Parser.RiseExpressionContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#fallExpression. - def visitFallExpression(self, ctx:OpenSCENARIO2Parser.FallExpressionContext): + def visitFallExpression(self, ctx: OpenSCENARIO2Parser.FallExpressionContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#elapsedExpression. - def visitElapsedExpression(self, ctx:OpenSCENARIO2Parser.ElapsedExpressionContext): + def visitElapsedExpression(self, ctx: OpenSCENARIO2Parser.ElapsedExpressionContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#everyExpression. - def visitEveryExpression(self, ctx:OpenSCENARIO2Parser.EveryExpressionContext): + def visitEveryExpression(self, ctx: OpenSCENARIO2Parser.EveryExpressionContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#boolExpression. - def visitBoolExpression(self, ctx:OpenSCENARIO2Parser.BoolExpressionContext): + def visitBoolExpression(self, ctx: OpenSCENARIO2Parser.BoolExpressionContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#durationExpression. - def visitDurationExpression(self, ctx:OpenSCENARIO2Parser.DurationExpressionContext): + def visitDurationExpression(self, ctx: OpenSCENARIO2Parser.DurationExpressionContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#fieldDeclaration. - def visitFieldDeclaration(self, ctx:OpenSCENARIO2Parser.FieldDeclarationContext): + def visitFieldDeclaration(self, ctx: OpenSCENARIO2Parser.FieldDeclarationContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#parameterDeclaration. - def visitParameterDeclaration(self, ctx:OpenSCENARIO2Parser.ParameterDeclarationContext): + def visitParameterDeclaration(self, ctx: OpenSCENARIO2Parser.ParameterDeclarationContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#variableDeclaration. - def visitVariableDeclaration(self, ctx:OpenSCENARIO2Parser.VariableDeclarationContext): + def visitVariableDeclaration(self, ctx: OpenSCENARIO2Parser.VariableDeclarationContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#sampleExpression. - def visitSampleExpression(self, ctx:OpenSCENARIO2Parser.SampleExpressionContext): + def visitSampleExpression(self, ctx: OpenSCENARIO2Parser.SampleExpressionContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#defaultValue. - def visitDefaultValue(self, ctx:OpenSCENARIO2Parser.DefaultValueContext): + def visitDefaultValue(self, ctx: OpenSCENARIO2Parser.DefaultValueContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#parameterWithDeclaration. - def visitParameterWithDeclaration(self, ctx:OpenSCENARIO2Parser.ParameterWithDeclarationContext): + def visitParameterWithDeclaration(self, ctx: OpenSCENARIO2Parser.ParameterWithDeclarationContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#parameterWithMember. - def visitParameterWithMember(self, ctx:OpenSCENARIO2Parser.ParameterWithMemberContext): + def visitParameterWithMember(self, ctx: OpenSCENARIO2Parser.ParameterWithMemberContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#constraintDeclaration. - def visitConstraintDeclaration(self, ctx:OpenSCENARIO2Parser.ConstraintDeclarationContext): + def visitConstraintDeclaration(self, ctx: OpenSCENARIO2Parser.ConstraintDeclarationContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#keepConstraintDeclaration. - def visitKeepConstraintDeclaration(self, ctx:OpenSCENARIO2Parser.KeepConstraintDeclarationContext): + def visitKeepConstraintDeclaration(self, ctx: OpenSCENARIO2Parser.KeepConstraintDeclarationContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#constraintQualifier. - def visitConstraintQualifier(self, ctx:OpenSCENARIO2Parser.ConstraintQualifierContext): + def visitConstraintQualifier(self, ctx: OpenSCENARIO2Parser.ConstraintQualifierContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#constraintExpression. - def visitConstraintExpression(self, ctx:OpenSCENARIO2Parser.ConstraintExpressionContext): + def visitConstraintExpression(self, ctx: OpenSCENARIO2Parser.ConstraintExpressionContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#removeDefaultDeclaration. - def visitRemoveDefaultDeclaration(self, ctx:OpenSCENARIO2Parser.RemoveDefaultDeclarationContext): + def visitRemoveDefaultDeclaration(self, ctx: OpenSCENARIO2Parser.RemoveDefaultDeclarationContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#parameterReference. - def visitParameterReference(self, ctx:OpenSCENARIO2Parser.ParameterReferenceContext): + def visitParameterReference(self, ctx: OpenSCENARIO2Parser.ParameterReferenceContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#modifierInvocation. - def visitModifierInvocation(self, ctx:OpenSCENARIO2Parser.ModifierInvocationContext): + def visitModifierInvocation(self, ctx: OpenSCENARIO2Parser.ModifierInvocationContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#behaviorExpression. - def visitBehaviorExpression(self, ctx:OpenSCENARIO2Parser.BehaviorExpressionContext): + def visitBehaviorExpression(self, ctx: OpenSCENARIO2Parser.BehaviorExpressionContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#behaviorSpecification. - def visitBehaviorSpecification(self, ctx:OpenSCENARIO2Parser.BehaviorSpecificationContext): + def visitBehaviorSpecification(self, ctx: OpenSCENARIO2Parser.BehaviorSpecificationContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#onDirective. - def visitOnDirective(self, ctx:OpenSCENARIO2Parser.OnDirectiveContext): + def visitOnDirective(self, ctx: OpenSCENARIO2Parser.OnDirectiveContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#onMember. - def visitOnMember(self, ctx:OpenSCENARIO2Parser.OnMemberContext): + def visitOnMember(self, ctx: OpenSCENARIO2Parser.OnMemberContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#doDirective. - def visitDoDirective(self, ctx:OpenSCENARIO2Parser.DoDirectiveContext): + def visitDoDirective(self, ctx: OpenSCENARIO2Parser.DoDirectiveContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#doMember. - def visitDoMember(self, ctx:OpenSCENARIO2Parser.DoMemberContext): + def visitDoMember(self, ctx: OpenSCENARIO2Parser.DoMemberContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#composition. - def visitComposition(self, ctx:OpenSCENARIO2Parser.CompositionContext): + def visitComposition(self, ctx: OpenSCENARIO2Parser.CompositionContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#compositionOperator. - def visitCompositionOperator(self, ctx:OpenSCENARIO2Parser.CompositionOperatorContext): + def visitCompositionOperator(self, ctx: OpenSCENARIO2Parser.CompositionOperatorContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#behaviorInvocation. - def visitBehaviorInvocation(self, ctx:OpenSCENARIO2Parser.BehaviorInvocationContext): + def visitBehaviorInvocation(self, ctx: OpenSCENARIO2Parser.BehaviorInvocationContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#behaviorWithDeclaration. - def visitBehaviorWithDeclaration(self, ctx:OpenSCENARIO2Parser.BehaviorWithDeclarationContext): + def visitBehaviorWithDeclaration(self, ctx: OpenSCENARIO2Parser.BehaviorWithDeclarationContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#behaviorWithMember. - def visitBehaviorWithMember(self, ctx:OpenSCENARIO2Parser.BehaviorWithMemberContext): + def visitBehaviorWithMember(self, ctx: OpenSCENARIO2Parser.BehaviorWithMemberContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#labelName. - def visitLabelName(self, ctx:OpenSCENARIO2Parser.LabelNameContext): + def visitLabelName(self, ctx: OpenSCENARIO2Parser.LabelNameContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#actorExpression. - def visitActorExpression(self, ctx:OpenSCENARIO2Parser.ActorExpressionContext): + def visitActorExpression(self, ctx: OpenSCENARIO2Parser.ActorExpressionContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#waitDirective. - def visitWaitDirective(self, ctx:OpenSCENARIO2Parser.WaitDirectiveContext): + def visitWaitDirective(self, ctx: OpenSCENARIO2Parser.WaitDirectiveContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#emitDirective. - def visitEmitDirective(self, ctx:OpenSCENARIO2Parser.EmitDirectiveContext): + def visitEmitDirective(self, ctx: OpenSCENARIO2Parser.EmitDirectiveContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#callDirective. - def visitCallDirective(self, ctx:OpenSCENARIO2Parser.CallDirectiveContext): + def visitCallDirective(self, ctx: OpenSCENARIO2Parser.CallDirectiveContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#untilDirective. - def visitUntilDirective(self, ctx:OpenSCENARIO2Parser.UntilDirectiveContext): + def visitUntilDirective(self, ctx: OpenSCENARIO2Parser.UntilDirectiveContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#methodInvocation. - def visitMethodInvocation(self, ctx:OpenSCENARIO2Parser.MethodInvocationContext): + def visitMethodInvocation(self, ctx: OpenSCENARIO2Parser.MethodInvocationContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#methodDeclaration. - def visitMethodDeclaration(self, ctx:OpenSCENARIO2Parser.MethodDeclarationContext): + def visitMethodDeclaration(self, ctx: OpenSCENARIO2Parser.MethodDeclarationContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#returnType. - def visitReturnType(self, ctx:OpenSCENARIO2Parser.ReturnTypeContext): + def visitReturnType(self, ctx: OpenSCENARIO2Parser.ReturnTypeContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#methodImplementation. - def visitMethodImplementation(self, ctx:OpenSCENARIO2Parser.MethodImplementationContext): + def visitMethodImplementation(self, ctx: OpenSCENARIO2Parser.MethodImplementationContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#methodQualifier. - def visitMethodQualifier(self, ctx:OpenSCENARIO2Parser.MethodQualifierContext): + def visitMethodQualifier(self, ctx: OpenSCENARIO2Parser.MethodQualifierContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#methodName. - def visitMethodName(self, ctx:OpenSCENARIO2Parser.MethodNameContext): + def visitMethodName(self, ctx: OpenSCENARIO2Parser.MethodNameContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#coverageDeclaration. - def visitCoverageDeclaration(self, ctx:OpenSCENARIO2Parser.CoverageDeclarationContext): + def visitCoverageDeclaration(self, ctx: OpenSCENARIO2Parser.CoverageDeclarationContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#coverDeclaration. - def visitCoverDeclaration(self, ctx:OpenSCENARIO2Parser.CoverDeclarationContext): + def visitCoverDeclaration(self, ctx: OpenSCENARIO2Parser.CoverDeclarationContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#recordDeclaration. - def visitRecordDeclaration(self, ctx:OpenSCENARIO2Parser.RecordDeclarationContext): + def visitRecordDeclaration(self, ctx: OpenSCENARIO2Parser.RecordDeclarationContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#coverageExpression. - def visitCoverageExpression(self, ctx:OpenSCENARIO2Parser.CoverageExpressionContext): + def visitCoverageExpression(self, ctx: OpenSCENARIO2Parser.CoverageExpressionContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#coverageUnit. - def visitCoverageUnit(self, ctx:OpenSCENARIO2Parser.CoverageUnitContext): + def visitCoverageUnit(self, ctx: OpenSCENARIO2Parser.CoverageUnitContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#coverageRange. - def visitCoverageRange(self, ctx:OpenSCENARIO2Parser.CoverageRangeContext): + def visitCoverageRange(self, ctx: OpenSCENARIO2Parser.CoverageRangeContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#coverageEvery. - def visitCoverageEvery(self, ctx:OpenSCENARIO2Parser.CoverageEveryContext): + def visitCoverageEvery(self, ctx: OpenSCENARIO2Parser.CoverageEveryContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#coverageEvent. - def visitCoverageEvent(self, ctx:OpenSCENARIO2Parser.CoverageEventContext): + def visitCoverageEvent(self, ctx: OpenSCENARIO2Parser.CoverageEventContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#coverageNameArgument. - def visitCoverageNameArgument(self, ctx:OpenSCENARIO2Parser.CoverageNameArgumentContext): + def visitCoverageNameArgument(self, ctx: OpenSCENARIO2Parser.CoverageNameArgumentContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#targetName. - def visitTargetName(self, ctx:OpenSCENARIO2Parser.TargetNameContext): + def visitTargetName(self, ctx: OpenSCENARIO2Parser.TargetNameContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#expression. - def visitExpression(self, ctx:OpenSCENARIO2Parser.ExpressionContext): + def visitExpression(self, ctx: OpenSCENARIO2Parser.ExpressionContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#ternaryOpExp. - def visitTernaryOpExp(self, ctx:OpenSCENARIO2Parser.TernaryOpExpContext): + def visitTernaryOpExp(self, ctx: OpenSCENARIO2Parser.TernaryOpExpContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#implication. - def visitImplication(self, ctx:OpenSCENARIO2Parser.ImplicationContext): + def visitImplication(self, ctx: OpenSCENARIO2Parser.ImplicationContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#disjunction. - def visitDisjunction(self, ctx:OpenSCENARIO2Parser.DisjunctionContext): + def visitDisjunction(self, ctx: OpenSCENARIO2Parser.DisjunctionContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#conjunction. - def visitConjunction(self, ctx:OpenSCENARIO2Parser.ConjunctionContext): + def visitConjunction(self, ctx: OpenSCENARIO2Parser.ConjunctionContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#inversion. - def visitInversion(self, ctx:OpenSCENARIO2Parser.InversionContext): + def visitInversion(self, ctx: OpenSCENARIO2Parser.InversionContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#relationExp. - def visitRelationExp(self, ctx:OpenSCENARIO2Parser.RelationExpContext): + def visitRelationExp(self, ctx: OpenSCENARIO2Parser.RelationExpContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#sumExp. - def visitSumExp(self, ctx:OpenSCENARIO2Parser.SumExpContext): + def visitSumExp(self, ctx: OpenSCENARIO2Parser.SumExpContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#relationalOp. - def visitRelationalOp(self, ctx:OpenSCENARIO2Parser.RelationalOpContext): + def visitRelationalOp(self, ctx: OpenSCENARIO2Parser.RelationalOpContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#termExp. - def visitTermExp(self, ctx:OpenSCENARIO2Parser.TermExpContext): + def visitTermExp(self, ctx: OpenSCENARIO2Parser.TermExpContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#additiveExp. - def visitAdditiveExp(self, ctx:OpenSCENARIO2Parser.AdditiveExpContext): + def visitAdditiveExp(self, ctx: OpenSCENARIO2Parser.AdditiveExpContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#additiveOp. - def visitAdditiveOp(self, ctx:OpenSCENARIO2Parser.AdditiveOpContext): + def visitAdditiveOp(self, ctx: OpenSCENARIO2Parser.AdditiveOpContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#multiplicativeExp. - def visitMultiplicativeExp(self, ctx:OpenSCENARIO2Parser.MultiplicativeExpContext): + def visitMultiplicativeExp(self, ctx: OpenSCENARIO2Parser.MultiplicativeExpContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#factorExp. - def visitFactorExp(self, ctx:OpenSCENARIO2Parser.FactorExpContext): + def visitFactorExp(self, ctx: OpenSCENARIO2Parser.FactorExpContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#multiplicativeOp. - def visitMultiplicativeOp(self, ctx:OpenSCENARIO2Parser.MultiplicativeOpContext): + def visitMultiplicativeOp(self, ctx: OpenSCENARIO2Parser.MultiplicativeOpContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#factor. - def visitFactor(self, ctx:OpenSCENARIO2Parser.FactorContext): + def visitFactor(self, ctx: OpenSCENARIO2Parser.FactorContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#primaryExpression. - def visitPrimaryExpression(self, ctx:OpenSCENARIO2Parser.PrimaryExpressionContext): + def visitPrimaryExpression(self, ctx: OpenSCENARIO2Parser.PrimaryExpressionContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#castExpression. - def visitCastExpression(self, ctx:OpenSCENARIO2Parser.CastExpressionContext): + def visitCastExpression(self, ctx: OpenSCENARIO2Parser.CastExpressionContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#functionApplicationExpression. - def visitFunctionApplicationExpression(self, ctx:OpenSCENARIO2Parser.FunctionApplicationExpressionContext): + def visitFunctionApplicationExpression(self, ctx: OpenSCENARIO2Parser.FunctionApplicationExpressionContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#fieldAccessExpression. - def visitFieldAccessExpression(self, ctx:OpenSCENARIO2Parser.FieldAccessExpressionContext): + def visitFieldAccessExpression(self, ctx: OpenSCENARIO2Parser.FieldAccessExpressionContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#elementAccessExpression. - def visitElementAccessExpression(self, ctx:OpenSCENARIO2Parser.ElementAccessExpressionContext): + def visitElementAccessExpression(self, ctx: OpenSCENARIO2Parser.ElementAccessExpressionContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#typeTestExpression. - def visitTypeTestExpression(self, ctx:OpenSCENARIO2Parser.TypeTestExpressionContext): + def visitTypeTestExpression(self, ctx: OpenSCENARIO2Parser.TypeTestExpressionContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#fieldAccess. - def visitFieldAccess(self, ctx:OpenSCENARIO2Parser.FieldAccessContext): + def visitFieldAccess(self, ctx: OpenSCENARIO2Parser.FieldAccessContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#primaryExp. - def visitPrimaryExp(self, ctx:OpenSCENARIO2Parser.PrimaryExpContext): + def visitPrimaryExp(self, ctx: OpenSCENARIO2Parser.PrimaryExpContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#valueExp. - def visitValueExp(self, ctx:OpenSCENARIO2Parser.ValueExpContext): + def visitValueExp(self, ctx: OpenSCENARIO2Parser.ValueExpContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#listConstructor. - def visitListConstructor(self, ctx:OpenSCENARIO2Parser.ListConstructorContext): + def visitListConstructor(self, ctx: OpenSCENARIO2Parser.ListConstructorContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#rangeConstructor. - def visitRangeConstructor(self, ctx:OpenSCENARIO2Parser.RangeConstructorContext): + def visitRangeConstructor(self, ctx: OpenSCENARIO2Parser.RangeConstructorContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#identifierReference. - def visitIdentifierReference(self, ctx:OpenSCENARIO2Parser.IdentifierReferenceContext): + def visitIdentifierReference(self, ctx: OpenSCENARIO2Parser.IdentifierReferenceContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#argumentListSpecification. - def visitArgumentListSpecification(self, ctx:OpenSCENARIO2Parser.ArgumentListSpecificationContext): + def visitArgumentListSpecification(self, ctx: OpenSCENARIO2Parser.ArgumentListSpecificationContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#argumentSpecification. - def visitArgumentSpecification(self, ctx:OpenSCENARIO2Parser.ArgumentSpecificationContext): + def visitArgumentSpecification(self, ctx: OpenSCENARIO2Parser.ArgumentSpecificationContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#argumentName. - def visitArgumentName(self, ctx:OpenSCENARIO2Parser.ArgumentNameContext): + def visitArgumentName(self, ctx: OpenSCENARIO2Parser.ArgumentNameContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#argumentList. - def visitArgumentList(self, ctx:OpenSCENARIO2Parser.ArgumentListContext): + def visitArgumentList(self, ctx: OpenSCENARIO2Parser.ArgumentListContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#positionalArgument. - def visitPositionalArgument(self, ctx:OpenSCENARIO2Parser.PositionalArgumentContext): + def visitPositionalArgument(self, ctx: OpenSCENARIO2Parser.PositionalArgumentContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#namedArgument. - def visitNamedArgument(self, ctx:OpenSCENARIO2Parser.NamedArgumentContext): + def visitNamedArgument(self, ctx: OpenSCENARIO2Parser.NamedArgumentContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#physicalLiteral. - def visitPhysicalLiteral(self, ctx:OpenSCENARIO2Parser.PhysicalLiteralContext): + def visitPhysicalLiteral(self, ctx: OpenSCENARIO2Parser.PhysicalLiteralContext): return self.visitChildren(ctx) - # Visit a parse tree produced by OpenSCENARIO2Parser#integerLiteral. - def visitIntegerLiteral(self, ctx:OpenSCENARIO2Parser.IntegerLiteralContext): + def visitIntegerLiteral(self, ctx: OpenSCENARIO2Parser.IntegerLiteralContext): return self.visitChildren(ctx) - -del OpenSCENARIO2Parser \ No newline at end of file +del OpenSCENARIO2Parser diff --git a/scenario_execution/test/common.py b/scenario_execution/test/common.py index bdf719f9..fbf21215 100644 --- a/scenario_execution/test/common.py +++ b/scenario_execution/test/common.py @@ -33,7 +33,7 @@ def reset(self): self.logs_debug = [] self.logs_warning = [] self.logs_error = [] - + def info(self, msg: str) -> None: self.logs.append(msg) self.logs_info.append(msg) diff --git a/scenario_execution/test/test_scenario_compositions.py b/scenario_execution/test/test_scenario_compositions.py index 0af6b6df..b4d4f659 100644 --- a/scenario_execution/test/test_scenario_compositions.py +++ b/scenario_execution/test/test_scenario_compositions.py @@ -164,7 +164,7 @@ def test_selector_no_memory(self): self.assertEqual(self.logger.logs_info[0], "B") self.assertEqual(self.logger.logs_info[1], "B") - def test_selector_no_memory(self): + def test_selector_no_memory_second_false(self): scenario_content = """ import osc.helpers diff --git a/scenario_execution_ros/scenario_execution_ros/actions/assert_lifecycle_state.py b/scenario_execution_ros/scenario_execution_ros/actions/assert_lifecycle_state.py index 7138b38a..1f2b339d 100644 --- a/scenario_execution_ros/scenario_execution_ros/actions/assert_lifecycle_state.py +++ b/scenario_execution_ros/scenario_execution_ros/actions/assert_lifecycle_state.py @@ -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 @@ -36,14 +36,14 @@ class AssertLifecycleStateState(Enum): class AssertLifecycleState(BaseAction): - def __init__(self, node_name: str, state_sequence: list, allow_initial_skip: bool, fail_on_unexpected: bool, keep_running: bool): + def __init__(self, node_name: str, state_sequence: list): super().__init__() self.current_state = AssertLifecycleStateState.IDLE self.node_name = node_name self.state_sequence = state_sequence - self.allow_initial_skip = allow_initial_skip - self.fail_on_unexpected = fail_on_unexpected - self.keep_running = keep_running + self.allow_initial_skip = None + self.fail_on_unexpected = None + self.keep_running = None self.node = None self.subscription = None self.initial_states_skipped = False @@ -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( @@ -65,17 +65,14 @@ def setup(self, **kwargs): service_get_state_name = "/" + self.node_name + "/get_state" self.client = self.node.create_client(GetState, service_get_state_name) - 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.") - + def execute(self, allow_initial_skip: bool, fail_on_unexpected: bool, keep_running: bool): 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 diff --git a/scenario_execution_ros/scenario_execution_ros/actions/assert_tf_moving.py b/scenario_execution_ros/scenario_execution_ros/actions/assert_tf_moving.py index 0e13c518..9134f010 100644 --- a/scenario_execution_ros/scenario_execution_ros/actions/assert_tf_moving.py +++ b/scenario_execution_ros/scenario_execution_ros/actions/assert_tf_moving.py @@ -20,23 +20,23 @@ 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 class AssertTfMoving(BaseAction): - 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): + def __init__(self, tf_topic_namespace: str): super().__init__() - self.frame_id = frame_id - self.parent_frame_id = parent_frame_id - self.timeout = timeout - self.threshold_translation = threshold_translation - self.threshold_rotation = threshold_rotation - self.wait_for_first_transform = wait_for_first_transform + self.frame_id = None + self.parent_frame_id = None + self.timeout = None + self.threshold_translation = None + self.threshold_rotation = None + self.wait_for_first_transform = None self.tf_topic_namespace = tf_topic_namespace - self.use_sim_time = use_sim_time + self.use_sim_time = None self.start_timeout = False self.timer = 0 self.transforms_received = 0 @@ -51,9 +51,8 @@ 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() tf_prefix = self.tf_topic_namespace if not tf_prefix.startswith('/') and tf_prefix != '': @@ -65,9 +64,7 @@ def setup(self, **kwargs): tf_static_topic=(tf_prefix + "/tf_static"), ) - 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.") + def execute(self, frame_id: str, parent_frame_id: str, timeout: int, threshold_translation: float, threshold_rotation: float, wait_for_first_transform: bool, use_sim_time: bool): self.frame_id = frame_id self.parent_frame_id = parent_frame_id self.timeout = timeout @@ -75,6 +72,7 @@ def execute(self, frame_id: str, parent_frame_id: str, timeout: int, threshold_t self.threshold_rotation = threshold_rotation self.wait_for_first_transform = wait_for_first_transform self.use_sim_time = use_sim_time + self.feedback_message = f"Waiting for transform {self.parent_frame_id} --> {self.frame_id}" # pylint: disable= attribute-defined-outside-init def update(self) -> py_trees.common.Status: now = time.time() diff --git a/scenario_execution_ros/scenario_execution_ros/actions/assert_topic_latency.py b/scenario_execution_ros/scenario_execution_ros/actions/assert_topic_latency.py index 601fade6..8c34a136 100644 --- a/scenario_execution_ros/scenario_execution_ros/actions/assert_topic_latency.py +++ b/scenario_execution_ros/scenario_execution_ros/actions/assert_topic_latency.py @@ -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): @@ -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): + def execute(self): 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: diff --git a/scenario_execution_ros/scenario_execution_ros/actions/odometry_distance_traveled.py b/scenario_execution_ros/scenario_execution_ros/actions/odometry_distance_traveled.py index d821e067..5f455265 100644 --- a/scenario_execution_ros/scenario_execution_ros/actions/odometry_distance_traveled.py +++ b/scenario_execution_ros/scenario_execution_ros/actions/odometry_distance_traveled.py @@ -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): @@ -27,10 +27,10 @@ class OdometryDistanceTraveled(BaseAction): Class to wait for a certain covered distance, based on odometry """ - def __init__(self, associated_actor, distance: float, namespace_override: str): + def __init__(self, associated_actor, namespace_override: str): super().__init__() self.namespace = associated_actor["namespace"] - self.distance_expected = distance + self.distance_expected = None self.distance_traveled = 0.0 self.previous_x = 0 self.previous_y = 0 @@ -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: @@ -57,9 +57,9 @@ def setup(self, **kwargs): self.subscriber = self.node.create_subscription( Odometry, namespace + '/odom', self._callback, 1000, callback_group=self.callback_group) - 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.") + def execute(self, associated_actor, distance: float): + if self.namespace != associated_actor["namespace"] and not self.namespace_override: + raise ActionError("Runtime change of namespace not supported.", action=self) self.distance_expected = distance self.distance_traveled = 0.0 self.previous_x = 0 diff --git a/scenario_execution_ros/scenario_execution_ros/actions/ros_action_call.py b/scenario_execution_ros/scenario_execution_ros/actions/ros_action_call.py index b906f537..7e3965a6 100644 --- a/scenario_execution_ros/scenario_execution_ros/actions/ros_action_call.py +++ b/scenario_execution_ros/scenario_execution_ros/actions/ros_action_call.py @@ -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): @@ -43,7 +43,7 @@ class RosActionCall(BaseAction): ros service call behavior """ - def __init__(self, action_name: str, action_type: str, data: str, transient_local: bool = False): + def __init__(self, action_name: str, action_type: str, transient_local: bool = False): super().__init__() self.node = None self.client = None @@ -54,7 +54,6 @@ def __init__(self, action_name: str, action_type: str, data: str, transient_loca self.action_name = action_name self.received_feedback = None self.data = None - self.parse_data(data) self.current_state = ActionCallActionState.IDLE self.cb_group = ReentrantCallbackGroup() self.transient_local = transient_local @@ -69,7 +68,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 datatype_in_list = self.action_type_string.split(".") try: @@ -77,7 +76,7 @@ def setup(self, **kwargs): 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, @@ -90,10 +89,7 @@ def setup(self, **kwargs): self.client = ActionClient(self.node, self.action_type, self.action_name, **client_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.") - + def execute(self, data: str): self.parse_data(data) self.current_state = ActionCallActionState.IDLE @@ -103,7 +99,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: """ diff --git a/scenario_execution_ros/scenario_execution_ros/actions/ros_bag_record.py b/scenario_execution_ros/scenario_execution_ros/actions/ros_bag_record.py index a40ae23b..e47faec1 100644 --- a/scenario_execution_ros/scenario_execution_ros/actions/ros_bag_record.py +++ b/scenario_execution_ros/scenario_execution_ros/actions/ros_bag_record.py @@ -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 @@ -38,24 +39,24 @@ class RosBagRecord(RunProcess): Class to execute ros bag recording """ - def __init__(self, topics: list, timestamp_suffix: bool, hidden_topics: bool, storage: str, use_sim_time: bool): + def __init__(self): super().__init__() self.bag_dir = None self.current_state = RosBagRecordActionState.WAITING_FOR_TOPICS self.command = None self.output_dir = None + self.topics = None 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 diff --git a/scenario_execution_ros/scenario_execution_ros/actions/ros_launch.py b/scenario_execution_ros/scenario_execution_ros/actions/ros_launch.py index d546d691..4e460df4 100644 --- a/scenario_execution_ros/scenario_execution_ros/actions/ros_launch.py +++ b/scenario_execution_ros/scenario_execution_ros/actions/ros_launch.py @@ -14,22 +14,20 @@ # # SPDX-License-Identifier: Apache-2.0 +from scenario_execution.actions.base_action import ActionError from scenario_execution.actions.run_process import RunProcess import signal class RosLaunch(RunProcess): - def __init__(self, package_name: str, launch_file: str, arguments: list, wait_for_shutdown: bool, shutdown_timeout: float): - super().__init__(None, wait_for_shutdown, shutdown_timeout, shutdown_signal=("", signal.SIGINT)) - def execute(self, package_name: str, launch_file: str, arguments: list, wait_for_shutdown: bool, shutdown_timeout: float): # pylint: disable=arguments-differ super().execute(None, wait_for_shutdown, shutdown_timeout, shutdown_signal=("", signal.SIGINT)) self.command = ["ros2", "launch", package_name, launch_file] if isinstance(arguments, list): for arg in arguments: if 'key' not in arg or 'value' not in arg: - raise ValueError(f'Invalid argument: {arg}') + raise ActionError(f'Invalid argument: {arg}', action=self) if arg["key"] is not None: self.command.append(f'{arg["key"]}:={arg["value"]}') self.logger.info(f'Command: {" ".join(self.command)}') diff --git a/scenario_execution_ros/scenario_execution_ros/actions/ros_log_check.py b/scenario_execution_ros/scenario_execution_ros/actions/ros_log_check.py index 617b6a16..49eb9288 100644 --- a/scenario_execution_ros/scenario_execution_ros/actions/ros_log_check.py +++ b/scenario_execution_ros/scenario_execution_ros/actions/ros_log_check.py @@ -19,7 +19,7 @@ import rclpy from rcl_interfaces.msg import Log from py_trees.common import Status -from scenario_execution.actions.base_action import BaseAction +from scenario_execution.actions.base_action import BaseAction, ActionError class RosLogCheck(BaseAction): @@ -27,17 +27,14 @@ class RosLogCheck(BaseAction): Class for scanning the ros log for specific content """ - def __init__(self, values: list, module_name: str): + def __init__(self): super().__init__() - if not isinstance(values, list): - raise TypeError(f'Value needs to be list of strings, got {type(values)}.') - else: - self.values = values + self.values = None self.subscriber = None self.node = None self.found = None - self.module_name = module_name + self.module_name = None def setup(self, **kwargs): """ @@ -48,7 +45,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_qos = QoSProfile( depth=100, diff --git a/scenario_execution_ros/scenario_execution_ros/actions/ros_service_call.py b/scenario_execution_ros/scenario_execution_ros/actions/ros_service_call.py index 7a3b5af8..d10a6bb7 100644 --- a/scenario_execution_ros/scenario_execution_ros/actions/ros_service_call.py +++ b/scenario_execution_ros/scenario_execution_ros/actions/ros_service_call.py @@ -22,7 +22,7 @@ from rclpy.qos import QoSProfile, DurabilityPolicy from rosidl_runtime_py.set_message import set_message_fields import py_trees # pylint: disable=import-error -from scenario_execution.actions.base_action import BaseAction +from scenario_execution.actions.base_action import BaseAction, ActionError class ServiceCallActionState(Enum): @@ -40,7 +40,7 @@ class RosServiceCall(BaseAction): ros service call behavior """ - def __init__(self, service_name: str, service_type: str, data: str, transient_local: bool = False): + def __init__(self, service_name: str, service_type: str, transient_local: bool = False): super().__init__() self.node = None self.client = None @@ -48,12 +48,7 @@ def __init__(self, service_name: str, service_type: str, data: str, transient_lo self.service_type_str = service_type self.service_type = None self.service_name = service_name - self.data_str = data - try: - trimmed_data = self.data_str.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 + self.data = None self.current_state = ServiceCallActionState.IDLE self.cb_group = ReentrantCallbackGroup() self.transient_local = transient_local @@ -68,7 +63,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 datatype_in_list = self.service_type_str.split(".") try: @@ -76,7 +71,7 @@ def setup(self, **kwargs): importlib.import_module(".".join(datatype_in_list[0:-1])), datatype_in_list[-1]) except ValueError as e: - raise ValueError(f"Invalid service_type '{self.service_type}':") from e + raise ActionError(f"Invalid service_type '{self.service_type}': {e}", action=self) from e client_kwargs = { "callback_group": self.cb_group, @@ -93,9 +88,12 @@ def setup(self, **kwargs): **client_kwargs ) - def execute(self, service_name: str, service_type: str, data: str, transient_local: bool): - if self.service_name != service_name or self.service_type_str != service_type or self.data_str != data or self.transient_local != transient_local: - raise ValueError("service_name, service_type and data arguments are not changeable during runtime.") + def execute(self, data: str): + try: + trimmed_data = data.encode('utf-8').decode('unicode_escape') + self.data = literal_eval(trimmed_data) + except Exception as e: # pylint: disable=broad-except + raise ActionError(f"Error while parsing sevice call data: {e}", action=self) from e self.current_state = ServiceCallActionState.IDLE def update(self) -> py_trees.common.Status: diff --git a/scenario_execution_ros/scenario_execution_ros/actions/ros_set_node_parameter.py b/scenario_execution_ros/scenario_execution_ros/actions/ros_set_node_parameter.py index 3464ad7c..5c87e947 100644 --- a/scenario_execution_ros/scenario_execution_ros/actions/ros_set_node_parameter.py +++ b/scenario_execution_ros/scenario_execution_ros/actions/ros_set_node_parameter.py @@ -25,14 +25,16 @@ class RosSetNodeParameter(RosServiceCall): class for setting a node parameter """ - def __init__(self, node_name: str, parameter_name: str, parameter_value: str): + def __init__(self, node_name: str, parameter_name: str): self.node_name = node_name self.parameter_name = parameter_name - self.parameter_value = parameter_value + self.parameter_value = None service_name = node_name + '/set_parameters' if not service_name.startswith('/'): service_name = '/' + service_name + super().__init__(service_name=service_name, service_type='rcl_interfaces.srv.SetParameters') + def execute(self, parameter_value: str): # pylint: disable=arguments-differ,arguments-renamed parameter_type = ParameterType.PARAMETER_STRING parameter_assign_name = 'string_value' if parameter_value.lower() == 'true' or parameter_value.lower() == 'false': @@ -63,14 +65,8 @@ def __init__(self, node_name: str, parameter_name: str, parameter_value: str): else: parameter_type = ParameterType.PARAMETER_STRING_ARRAY parameter_assign_name = 'string_array_value' - - super().__init__(service_name=service_name, - service_type='rcl_interfaces.srv.SetParameters', - data='{ "parameters": [{ "name": "' + parameter_name + '", "value": { "type": ' + str(parameter_type) + ', "' + parameter_assign_name + '": ' + parameter_value + '}}]}') - - def execute(self, node_name: str, parameter_name: str, parameter_value: str): # pylint: disable=arguments-differ,arguments-renamed - if self.node_name != node_name or self.parameter_name != parameter_name or self.parameter_value != parameter_value: - raise ValueError("node_name, parameter_name and parameter_value are not changeable during runtime.") + super().execute(data='{ "parameters": [{ "name": "' + self.parameter_name + '", "value": { "type": ' + + str(parameter_type) + ', "' + parameter_assign_name + '": ' + parameter_value + '}}]}') @staticmethod def is_float(element: any) -> bool: diff --git a/scenario_execution_ros/scenario_execution_ros/actions/ros_topic_check_data.py b/scenario_execution_ros/scenario_execution_ros/actions/ros_topic_check_data.py index d1c1255c..e7289485 100644 --- a/scenario_execution_ros/scenario_execution_ros/actions/ros_topic_check_data.py +++ b/scenario_execution_ros/scenario_execution_ros/actions/ros_topic_check_data.py @@ -21,7 +21,7 @@ from rosidl_runtime_py.set_message import set_message_fields from scenario_execution_ros.actions.conversions import get_qos_preset_profile, get_comparison_operator, get_ros_message_type import builtins -from scenario_execution.actions.base_action import BaseAction +from scenario_execution.actions.base_action import BaseAction, ActionError class RosTopicCheckData(BaseAction): @@ -32,23 +32,18 @@ class RosTopicCheckData(BaseAction): def __init__(self, topic_name: str, topic_type: str, - qos_profile: tuple, member_name: str, - expected_value: str, - comparison_operator: int, - fail_if_no_data: bool, - fail_if_bad_comparison: bool, - wait_for_first_message: bool): + qos_profile: tuple): super().__init__() self.topic_name = topic_name self.topic_type = topic_type - self.qos_profile = qos_profile self.member_name = member_name - self.set_expected_value(expected_value) - self.comparison_operator = get_comparison_operator(comparison_operator) - self.fail_if_no_data = fail_if_no_data - self.fail_if_bad_comparison = fail_if_bad_comparison - self.wait_for_first_message = wait_for_first_message + self.qos_profile = qos_profile + self.expected_value = None + self.comparison_operator = None + self.fail_if_no_data = None + self.fail_if_bad_comparison = None + self.wait_for_first_message = None self.last_msg = None self.found = None @@ -61,7 +56,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 + + # check if msg type exists and has member + try: + msg = get_ros_message_type(self.topic_type)() + if self.member_name: + getattr(msg, self.member_name) + except (ValueError, AttributeError) as e: + raise ActionError(f"Member '{self.member_name}' not found in topic type '{self.topic_type}'.", action=self) from e self.subscriber = self.node.create_subscription( msg_type=get_ros_message_type(self.topic_type), @@ -73,18 +76,11 @@ def setup(self, **kwargs): self.feedback_message = f"Waiting for data on {self.topic_name}" # pylint: disable= attribute-defined-outside-init def execute(self, - topic_name: str, - topic_type: str, - qos_profile: tuple, - member_name: str, expected_value: str, comparison_operator: int, fail_if_no_data: bool, fail_if_bad_comparison: bool, wait_for_first_message: bool): - if self.topic_name != topic_name or self.topic_type != topic_type or self.qos_profile != qos_profile: - raise ValueError("Updating topic parameters not supported.") - self.member_name = member_name self.set_expected_value(expected_value) self.comparison_operator = get_comparison_operator(comparison_operator) self.fail_if_no_data = fail_if_no_data @@ -115,7 +111,7 @@ def _callback(self, msg): self.feedback_message = f"Received message does not contain expected value." def check_data(self, msg): - if msg is None: + if msg is None or self.member_name is None or self.expected_value is None: return if self.member_name == "": @@ -130,7 +126,7 @@ def check_data(self, msg): def set_expected_value(self, expected_value_string): if not isinstance(expected_value_string, str): - raise ValueError("Only string allowed as expected_value.") + raise ActionError("Only string allowed as expected_value.", action=self) error_string = "" try: parsed_value = literal_eval("".join(expected_value_string.split('\\'))) @@ -145,5 +141,5 @@ def set_expected_value(self, expected_value_string): self.expected_value = parsed_value else: set_message_fields(self.expected_value, parsed_value) - except TypeError as e: - raise ValueError(f"Could not parse '{expected_value_string}'. {error_string}") from e + except (TypeError, AttributeError) as e: + raise ActionError(f"Could not parse '{expected_value_string}'. {error_string}", action=self) from e diff --git a/scenario_execution_ros/scenario_execution_ros/actions/ros_topic_monitor.py b/scenario_execution_ros/scenario_execution_ros/actions/ros_topic_monitor.py index 1279c0d5..74d73958 100644 --- a/scenario_execution_ros/scenario_execution_ros/actions/ros_topic_monitor.py +++ b/scenario_execution_ros/scenario_execution_ros/actions/ros_topic_monitor.py @@ -15,7 +15,7 @@ # SPDX-License-Identifier: Apache-2.0 from scenario_execution_ros.actions.conversions import get_qos_preset_profile, get_ros_message_type -from scenario_execution.actions.base_action import BaseAction +from scenario_execution.actions.base_action import BaseAction, ActionError from scenario_execution.model.types import VariableReference import rclpy import py_trees @@ -24,10 +24,10 @@ class RosTopicMonitor(BaseAction): - def __init__(self, topic_name: str, topic_type: str, member_name: str, target_variable: object, qos_profile: tuple): + def __init__(self, topic_name: str, topic_type: str, qos_profile: tuple): super().__init__(resolve_variable_reference_arguments_in_execute=False) self.target_variable = None - self.member_name = member_name + self.member_name = None self.topic_type = topic_type self.qos_profile = qos_profile self.topic_name = topic_name @@ -43,7 +43,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 msg_type = get_ros_message_type(self.topic_type) @@ -59,11 +59,9 @@ def setup(self, **kwargs): ) self.feedback_message = f"Monitoring data on {self.topic_name}" # pylint: disable= attribute-defined-outside-init - def execute(self, topic_name: str, topic_type: str, member_name: str, target_variable: object, qos_profile: tuple): - if self.topic_name != topic_name or self.topic_type != topic_type or self.qos_profile != qos_profile: - raise ValueError("Updating topic parameters not supported.") + def execute(self, member_name: str, target_variable: object): if not isinstance(target_variable, VariableReference): - raise ValueError(f"'target_variable' is expected to be a variable reference.") + raise ActionError(f"'target_variable' is expected to be a variable reference.", action=self) self.target_variable = target_variable self.member_name = member_name @@ -75,11 +73,11 @@ def _callback(self, msg): self.target_variable.set_value(self.get_value(msg)) def get_value(self, msg): - if self.member_name != "": + if self.member_name is not None and self.member_name != "": check_attr = operator.attrgetter(self.member_name) try: return check_attr(msg) except AttributeError as e: - raise ValueError(f"invalid member_name '{self.member_name}'") from e + raise ActionError(f"invalid member_name '{self.member_name}'", action=self) from e else: return msg diff --git a/scenario_execution_ros/scenario_execution_ros/actions/ros_topic_publish.py b/scenario_execution_ros/scenario_execution_ros/actions/ros_topic_publish.py index 8d4baf8c..05fb2b49 100644 --- a/scenario_execution_ros/scenario_execution_ros/actions/ros_topic_publish.py +++ b/scenario_execution_ros/scenario_execution_ros/actions/ros_topic_publish.py @@ -23,7 +23,7 @@ from py_trees.common import Status from scenario_execution_ros.actions.conversions import get_qos_preset_profile, get_ros_message_type -from scenario_execution.actions.base_action import BaseAction +from scenario_execution.actions.base_action import BaseAction, ActionError class RosTopicPublish(BaseAction): @@ -31,7 +31,7 @@ class RosTopicPublish(BaseAction): class for publish a message on a ROS topic """ - def __init__(self, topic_type: str, topic_name: str, value: str, qos_profile: tuple): + def __init__(self, topic_type: str, topic_name: str, qos_profile: tuple): super().__init__() self.qos_profile = qos_profile self.topic_type = topic_type @@ -48,24 +48,24 @@ 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_type = get_ros_message_type(self.topic_type) - self.msg_to_pub = topic_type() - self.publisher = self.node.create_publisher( - msg_type=topic_type, - topic=self.topic_name, - qos_profile=get_qos_preset_profile(self.qos_profile) - ) - - def execute(self, topic_type: str, topic_name: str, value: str, qos_profile: tuple): - if self.topic_name != topic_name or self.topic_type != topic_type or self.qos_profile != qos_profile: - raise ValueError("Updating topic parameters not supported.") + try: + topic_type = get_ros_message_type(self.topic_type) + self.msg_to_pub = topic_type() + self.publisher = self.node.create_publisher( + msg_type=topic_type, + topic=self.topic_name, + qos_profile=get_qos_preset_profile(self.qos_profile) + ) + except ValueError as e: + raise ActionError(f"{e}", action=self) from e + def execute(self, value: str): if isinstance(value, str): parsed_value = literal_eval("".join(value.split('\\'))) if not isinstance(parsed_value, dict): - raise TypeError(f'Parsed value needs type "dict", got {type(parsed_value)}.') + raise ActionError(f'Parsed value needs type "dict", got {type(parsed_value)}.', action=self) set_message_fields(self.msg_to_pub, parsed_value) elif isinstance(value, dict): set_message_fields(self.msg_to_pub, value) diff --git a/scenario_execution_ros/scenario_execution_ros/actions/ros_topic_wait_for_data.py b/scenario_execution_ros/scenario_execution_ros/actions/ros_topic_wait_for_data.py index f45cadc9..9686cb1c 100644 --- a/scenario_execution_ros/scenario_execution_ros/actions/ros_topic_wait_for_data.py +++ b/scenario_execution_ros/scenario_execution_ros/actions/ros_topic_wait_for_data.py @@ -15,7 +15,7 @@ # SPDX-License-Identifier: Apache-2.0 from scenario_execution_ros.actions.conversions import get_qos_preset_profile, get_ros_message_type -from scenario_execution.actions.base_action import BaseAction +from scenario_execution.actions.base_action import BaseAction, ActionError import rclpy import py_trees @@ -48,7 +48,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.subscriber = self.node.create_subscription( msg_type=get_ros_message_type(self.topic_type), @@ -59,9 +59,7 @@ def setup(self, **kwargs): ) self.feedback_message = f"Waiting for data on {self.topic_name}" # pylint: disable= attribute-defined-outside-init - def execute(self, topic_name, topic_type, qos_profile): - if self.topic_name != topic_name or self.topic_type != topic_type or self.qos_profile != qos_profile: - raise ValueError("Updating topic parameters not supported.") + def execute(self): self.found = False def update(self) -> py_trees.common.Status: diff --git a/scenario_execution_ros/scenario_execution_ros/actions/ros_topic_wait_for_topics.py b/scenario_execution_ros/scenario_execution_ros/actions/ros_topic_wait_for_topics.py index 58202f5e..3f67a134 100644 --- a/scenario_execution_ros/scenario_execution_ros/actions/ros_topic_wait_for_topics.py +++ b/scenario_execution_ros/scenario_execution_ros/actions/ros_topic_wait_for_topics.py @@ -16,7 +16,7 @@ import py_trees from rclpy.node import Node -from scenario_execution.actions.base_action import BaseAction +from scenario_execution.actions.base_action import BaseAction, ActionError class RosTopicWaitForTopics(BaseAction): @@ -41,7 +41,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 def update(self) -> py_trees.common.Status: """ diff --git a/scenario_execution_ros/scenario_execution_ros/actions/tf_close_to.py b/scenario_execution_ros/scenario_execution_ros/actions/tf_close_to.py index ae81c385..7eb668e5 100644 --- a/scenario_execution_ros/scenario_execution_ros/actions/tf_close_to.py +++ b/scenario_execution_ros/scenario_execution_ros/actions/tf_close_to.py @@ -27,7 +27,7 @@ from tf2_ros import TransformException # pylint: disable= no-name-in-module from .common import NamespacedTransformListener -from scenario_execution.actions.base_action import BaseAction +from scenario_execution.actions.base_action import BaseAction, ActionError class TfCloseTo(BaseAction): @@ -79,7 +79,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 try: self.marker_handler = kwargs['marker_handler'] @@ -87,7 +87,7 @@ def setup(self, **kwargs): error_message = "didn't find 'marker_handler' 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 map --> base_link" # pylint: disable= attribute-defined-outside-init self.tf_buffer = Buffer() tf_prefix = self.namespace diff --git a/scenario_execution_ros/scenario_execution_ros/external_methods/__init__.py b/scenario_execution_ros/scenario_execution_ros/external_methods/__init__.py new file mode 100644 index 00000000..3ba13780 --- /dev/null +++ b/scenario_execution_ros/scenario_execution_ros/external_methods/__init__.py @@ -0,0 +1,15 @@ +# Copyright (C) 2024 Intel Corporation +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, +# software distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions +# and limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 diff --git a/scenario_execution_ros/scenario_execution_ros/external_methods/msg_conversion.py b/scenario_execution_ros/scenario_execution_ros/external_methods/msg_conversion.py new file mode 100644 index 00000000..1cbb9f17 --- /dev/null +++ b/scenario_execution_ros/scenario_execution_ros/external_methods/msg_conversion.py @@ -0,0 +1,50 @@ +# Copyright (C) 2024 Intel Corporation +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, +# software distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions +# and limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 +from geometry_msgs.msg import PoseWithCovarianceStamped +import json +from rosidl_runtime_py.convert import message_to_ordereddict + +from transforms3d.euler import quat2euler + + +def get_object_member(in_value, member_name=""): + target = in_value + if member_name: + splitted_member = member_name.split('.') + for mem in splitted_member: + if not hasattr(target, mem): + raise ValueError(f"Member '{mem}' not found in '{target}") + target = getattr(target, mem) + return target + + +def to_dict(in_value, member_name=""): + target = get_object_member(in_value, member_name) + return json.loads(json.dumps(message_to_ordereddict(target))) + + +def to_pose_3d(in_value): + if isinstance(in_value, PoseWithCovarianceStamped): + pose3d = {} + pose3d["position"] = to_dict(in_value.pose.pose.position) + roll, pitch, yaw = quat2euler([in_value.pose.pose.orientation.w, in_value.pose.pose.orientation.x, + in_value.pose.pose.orientation.y, in_value.pose.pose.orientation.z]) + pose3d["orientation"] = {'roll': roll, 'pitch': pitch, 'yaw': yaw} + return pose3d + elif isinstance(in_value, dict) and in_value == {}: # allow empty input to enable expression evaluation + return in_value + else: + raise ValueError(f"to_pose3d not implemented for type {type(in_value)}") diff --git a/scenario_execution_ros/scenario_execution_ros/lib_osc/ros.osc b/scenario_execution_ros/scenario_execution_ros/lib_osc/ros.osc index e74b003b..18ae923d 100644 --- a/scenario_execution_ros/scenario_execution_ros/lib_osc/ros.osc +++ b/scenario_execution_ros/scenario_execution_ros/lib_osc/ros.osc @@ -26,7 +26,11 @@ enum lifecycle_state: [ actor differential_drive_robot inherits robot: namespace: string = '' - + +struct msg_conversion: + def get_object_member(in_value: string, member_name: string = "") -> string is external scenario_execution_ros.external_methods.msg_conversion.get_object_member() + def to_pose_3d(in_value: string) -> pose_3d is external scenario_execution_ros.external_methods.msg_conversion.to_pose_3d() + action action_call: # Call a ros action and wait for the result action_name: string # name of the action to connect to diff --git a/scenario_execution_ros/test/test_check_data.py b/scenario_execution_ros/test/test_check_data.py index c3e33066..f34b3861 100644 --- a/scenario_execution_ros/test/test_check_data.py +++ b/scenario_execution_ros/test/test_check_data.py @@ -91,6 +91,31 @@ def test_success_member(self): self.execute(scenario_content) self.assertTrue(self.scenario_execution_ros.process_results()) + def test_fail_unknown_type(self): + scenario_content = """ +import osc.ros + +scenario test: + do parallel: + test: serial: + wait elapsed(1s) + topic_publish( + topic_name: '/bla', + topic_type: 'std_msgs.msg.Bool', + value: '{\\\"data\\\": True}') + receive: serial: + check_data( + topic_name: '/bla', + topic_type: 'std_msgs.msg.UNKNOWN', + expected_value: 'True') + emit end + time_out: serial: + wait elapsed(10s) + emit fail +""" + self.execute(scenario_content) + self.assertFalse(self.scenario_execution_ros.process_results()) + def test_fail_unknown_member(self): scenario_content = """ import osc.ros @@ -114,9 +139,8 @@ def test_fail_unknown_member(self): wait elapsed(10s) emit fail """ - parsed_tree = self.parser.parse_input_stream(InputStream(scenario_content)) - model = self.parser.create_internal_model(parsed_tree, self.tree, "test.osc", False) - self.assertRaises(ValueError, create_py_tree, model, self.tree, self.parser.logger, False) + self.execute(scenario_content) + self.assertFalse(self.scenario_execution_ros.process_results()) def test_fail_member_value_differ(self): scenario_content = """ diff --git a/scenario_execution_ros/test/test_external_methods_msg_conversion.py b/scenario_execution_ros/test/test_external_methods_msg_conversion.py new file mode 100644 index 00000000..58fe1728 --- /dev/null +++ b/scenario_execution_ros/test/test_external_methods_msg_conversion.py @@ -0,0 +1,102 @@ +# Copyright (C) 2024 Intel Corporation +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, +# software distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions +# and limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + + +import os +import unittest +import rclpy +import py_trees +from scenario_execution_ros import ROSScenarioExecution +from scenario_execution.model.osc2_parser import OpenScenario2Parser +from scenario_execution.model.model_to_py_tree import create_py_tree +from scenario_execution.model.model_blackboard import create_py_tree_blackboard +from scenario_execution.utils.logging import Logger +from antlr4.InputStream import InputStream + +os.environ["PYTHONUNBUFFERED"] = '1' + + +class TestExternalMethodsMsgConversion(unittest.TestCase): + # pylint: disable=missing-function-docstring + + def setUp(self): + rclpy.init() + self.parser = OpenScenario2Parser(Logger('test', False)) + self.scenario_execution_ros = ROSScenarioExecution() + self.tree = py_trees.composites.Sequence(name="", memory=True) + + def execute(self, scenario_content): + parsed_tree = self.parser.parse_input_stream(InputStream(scenario_content)) + model = self.parser.create_internal_model(parsed_tree, self.tree, "test.osc", False) + create_py_tree_blackboard(model, self.tree, self.parser.logger, False) + self.tree = create_py_tree(model, self.tree, self.parser.logger, False) + self.scenario_execution_ros.tree = self.tree + self.scenario_execution_ros.run() + + def tearDown(self): + rclpy.try_shutdown() + + def test_get_object_member(self): + scenario_content = """ +import osc.ros +import osc.helpers + +struct current_state: + var test_pose: string + +scenario test_success: + timeout(10s) + current: current_state + + do parallel: + topic_monitor('/test_pose', 'geometry_msgs.msg.PoseWithCovarianceStamped', current.test_pose) + serial: + wait elapsed(0.5s) + topic_publish('/test_pose', 'geometry_msgs.msg.PoseWithCovarianceStamped', "{ \\\'pose\\\': { \\\'pose\\\': { \\\'position\\\': { \\\'x\\\': 42 }}}}") + serial: + wait elapsed(3s) + topic_publish('/pose_only', 'geometry_msgs.msg.Pose', msg_conversion.get_object_member(current.test_pose, "pose.pose")) + + serial: + check_data('/pose_only', 'geometry_msgs.msg.Pose', expected_value: '{ \\\"position\\\": { \\\"x\\\": 42 }}') + emit end +""" + self.execute(scenario_content) + self.assertTrue(self.scenario_execution_ros.process_results()) + + def test_to_pose_3d(self): + scenario_content = """ +import osc.ros +import osc.helpers + +struct current_state: + var test_pose: string + +scenario test_success: + timeout(10s) + current: current_state + test_pose : pose_3d = pose_3d(position_3d(x: 42)) + do parallel: + topic_monitor('/test_pose', 'geometry_msgs.msg.PoseWithCovarianceStamped', current.test_pose) + serial: + wait elapsed(0.5s) + topic_publish('/test_pose', 'geometry_msgs.msg.PoseWithCovarianceStamped', "{ \\\'pose\\\': { \\\'pose\\\': { \\\'position\\\': { \\\'x\\\': 42 }, \\\'orientation\\\': { \\\'w\\\': 1 }}}}") + serial: + wait test_pose == msg_conversion.to_pose_3d(current.test_pose) + emit end +""" + self.execute(scenario_content) + self.assertTrue(self.scenario_execution_ros.process_results()) diff --git a/simulation/gazebo/gazebo_static_camera/launch/spawn_static_camera_launch.py b/simulation/gazebo/gazebo_static_camera/launch/spawn_static_camera_launch.py index 3a248ff8..407716e6 100644 --- a/simulation/gazebo/gazebo_static_camera/launch/spawn_static_camera_launch.py +++ b/simulation/gazebo/gazebo_static_camera/launch/spawn_static_camera_launch.py @@ -13,11 +13,11 @@ # and limitations under the License. # # SPDX-License-Identifier: Apache-2.0 - +import tempfile from ament_index_python.packages import get_package_share_directory from launch import LaunchDescription -from launch.actions import DeclareLaunchArgument +from launch.actions import DeclareLaunchArgument, ExecuteProcess from launch.substitutions import LaunchConfiguration from launch.substitutions.path_join_substitution import PathJoinSubstitution @@ -29,6 +29,15 @@ DeclareLaunchArgument('world_name', default_value='default', description='World name'), + + DeclareLaunchArgument('update_rate', default_value='5', + description='Update rate of the sensor'), + + DeclareLaunchArgument('image_width', default_value='320', + description='Width of camera image'), + + DeclareLaunchArgument('image_height', default_value='240', + description='Height of camera image'), ] for pose_element in ['x', 'y', 'z', 'roll', 'pitch', 'yaw']: @@ -41,10 +50,17 @@ def generate_launch_description(): camera_name = LaunchConfiguration('camera_name') world_name = LaunchConfiguration('world_name') + update_rate = LaunchConfiguration('update_rate') + image_width = LaunchConfiguration('image_width') + image_height = LaunchConfiguration('image_height') + camera_sdf = tempfile.NamedTemporaryFile(prefix='gazebo_static_camera_', suffix='.sdf', delete=False) x, y, z = LaunchConfiguration('x'), LaunchConfiguration('y'), LaunchConfiguration('z') roll, pitch, yaw = LaunchConfiguration('roll'), LaunchConfiguration('pitch'), LaunchConfiguration('yaw') + camera_sdf_xacro = ExecuteProcess( + cmd=['xacro', '-o', camera_sdf.name, ['update_rate:=', update_rate], ['image_width:=', image_width], ['image_height:=', image_height], PathJoinSubstitution([gazebo_static_camera_dir, 'models', 'camera.sdf.xacro'])]) + camera_bridge = Node( package='ros_gz_bridge', executable='parameter_bridge', @@ -80,11 +96,12 @@ def generate_launch_description(): '-R', roll, '-P', pitch, '-Y', yaw, - '-file', PathJoinSubstitution([gazebo_static_camera_dir, 'models', 'camera.sdf'])], + '-file', camera_sdf.name], output='screen' ) ld = LaunchDescription(ARGUMENTS) + ld.add_action(camera_sdf_xacro) ld.add_action(camera_bridge) ld.add_action(spawn_camera) return ld diff --git a/simulation/gazebo/gazebo_static_camera/models/camera.sdf b/simulation/gazebo/gazebo_static_camera/models/camera.sdf.xacro similarity index 75% rename from simulation/gazebo/gazebo_static_camera/models/camera.sdf rename to simulation/gazebo/gazebo_static_camera/models/camera.sdf.xacro index 32b945e3..28ee7986 100644 --- a/simulation/gazebo/gazebo_static_camera/models/camera.sdf +++ b/simulation/gazebo/gazebo_static_camera/models/camera.sdf.xacro @@ -1,5 +1,9 @@ - + + + + + true @@ -30,8 +34,8 @@ 1.047 - 320 - 240 + $(arg image_width) + $(arg image_height) 0.1 @@ -39,7 +43,7 @@ 1 - 5 + $(arg update_rate) true diff --git a/simulation/gazebo/gazebo_static_camera/package.xml b/simulation/gazebo/gazebo_static_camera/package.xml index 7aafd60c..62b5d6bd 100644 --- a/simulation/gazebo/gazebo_static_camera/package.xml +++ b/simulation/gazebo/gazebo_static_camera/package.xml @@ -11,6 +11,7 @@ rclpy ros_gz_bridge ros_ign_gazebo + xacro ament_copyright ament_flake8 diff --git a/test/scenario_execution_test/scenario_execution_test/actions/actor_set_value.py b/test/scenario_execution_test/scenario_execution_test/actions/actor_set_value.py index 0008e2bf..c54a7a82 100644 --- a/test/scenario_execution_test/scenario_execution_test/actions/actor_set_value.py +++ b/test/scenario_execution_test/scenario_execution_test/actions/actor_set_value.py @@ -20,6 +20,9 @@ class ActorSetValue(BaseAction): + def __init__(self, associated_actor): + super().__init__() + def setup(self, **kwargs): self.i = 0 self.value = None