Skip to content

Commit

Permalink
Refactor Node action into description classes
Browse files Browse the repository at this point in the history
Distro A; OPSEC #4584

Signed-off-by: Roger Strain <rstrain@swri.org>
  • Loading branch information
Roger Strain committed Jan 25, 2021
1 parent 06d049e commit 56a5946
Show file tree
Hide file tree
Showing 8 changed files with 106 additions and 63 deletions.
45 changes: 13 additions & 32 deletions launch_ros/launch_ros/actions/node.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,18 +14,12 @@

"""Module for the Node action."""

import os
import pathlib
from tempfile import NamedTemporaryFile
from typing import Dict
from typing import Iterable
from typing import List
from typing import Optional
from typing import Text # noqa: F401
from typing import Tuple # noqa: F401
from typing import Union

from launch.action import Action
from launch.actions import ExecuteLocal
from launch.actions import ExecuteProcess
from launch.frontend import Entity
Expand All @@ -34,32 +28,13 @@
from launch.frontend.type_utils import get_data_type_from_identifier

from launch.launch_context import LaunchContext
import launch.logging
from launch.some_substitutions_type import SomeSubstitutionsType
from launch.substitutions import LocalSubstitution
from launch.utilities import ensure_argument_type
from launch.utilities import normalize_to_list_of_substitutions
from launch.utilities import perform_substitutions

from launch_ros.descriptions import Node as NodeDescription
from launch_ros.descriptions import RosExecutable
from launch_ros.descriptions import Parameter
from launch_ros.descriptions import ParameterFile
from launch_ros.descriptions import RosExecutable
from launch_ros.parameters_type import SomeParameters
from launch_ros.remap_rule_type import SomeRemapRules
from launch_ros.substitutions import ExecutableInPackage
from launch_ros.utilities import add_node_name
from launch_ros.utilities import evaluate_parameters
from launch_ros.utilities import get_node_name_count
from launch_ros.utilities import make_namespace_absolute
from launch_ros.utilities import normalize_parameters
from launch_ros.utilities import normalize_remap_rules
from launch_ros.utilities import prefix_namespace

from rclpy.validate_namespace import validate_namespace
from rclpy.validate_node_name import validate_node_name

import yaml


@expose_action('node')
Expand Down Expand Up @@ -138,11 +113,19 @@ def __init__(
passed to the node as ROS remapping rules
:param: arguments list of extra arguments for the node
"""

self.__node_desc = NodeDescription(node_name=name, namespace=namespace, parameters=parameters, remappings=remappings, arguments=arguments)
self.__ros_exec = RosExecutable(package=package, executable_name=executable, nodes=[self.__node_desc])
self.__node_desc = NodeDescription(node_name=name, node_namespace=namespace,
parameters=parameters, remappings=remappings,
arguments=arguments)
self.__ros_exec = RosExecutable(package=package, executable=executable,
nodes=[self.__node_desc])
super().__init__(process_description=self.__ros_exec, **kwargs)

def _perform_substitutions(self, lc: LaunchContext):
self.__node_desc.prepare(lc, self.__ros_exec)

def is_node_name_fully_specified(self):
return self.__node_desc.is_node_name_fully_specified()

@staticmethod
def parse_nested_parameters(params, parser):
"""Normalize parameters as expected by Node constructor argument."""
Expand Down Expand Up @@ -249,9 +232,7 @@ def parse(cls, entity: Entity, parser: Parser):
@property
def node_name(self):
"""Getter for node_name."""
if self.__node_desc.final_node_name is None:
raise RuntimeError("cannot access 'node_name' before executing action")
return self.__node_desc.final_node_name
return self.__node_desc.node_name

@property
def expanded_node_namespace(self):
Expand Down
72 changes: 51 additions & 21 deletions launch_ros/launch_ros/descriptions/node.py
Original file line number Diff line number Diff line change
Expand Up @@ -24,29 +24,39 @@

import os
import pathlib
import yaml

from tempfile import NamedTemporaryFile

from typing import Dict
from typing import Iterable
from typing import List
from typing import Optional
from typing import Text
from typing import Tuple
from typing import Union

from launch import LaunchContext
from launch import SomeSubstitutionsType
from launch.descriptions import Executable
import launch.logging
from launch.substitutions import LocalSubstitution
from launch.utilities import ensure_argument_type
from launch.utilities import normalize_to_list_of_substitutions
from launch.utilities import perform_substitutions

from launch_ros.utilities import add_node_name
from launch_ros.utilities import evaluate_parameters
from launch_ros.utilities import get_node_name_count
from launch_ros.utilities import make_namespace_absolute
from launch_ros.utilities import normalize_parameters
from launch_ros.utilities import normalize_remap_rules
from launch_ros.utilities import prefix_namespace

from rclpy.validate_namespace import validate_namespace
from rclpy.validate_node_name import validate_node_name

import yaml

from .node_trait import NodeTrait
from ..parameter_descriptions import Parameter
from ..parameters_type import SomeParameters
Expand Down Expand Up @@ -114,11 +124,16 @@ def __init__(
:param: arguments list of extra arguments for the node
:param: traits list of special traits of the node
"""
if parameters is not None:
ensure_argument_type(parameters, (list), 'parameters', 'Node')
# All elements in the list are paths to files with parameters (or substitutions that
# evaluate to paths), or dictionaries of parameters (fields can be substitutions).
normalized_params = normalize_parameters(parameters)

self.__node_name = node_name
self.__node_namespace = node_namespace
self.__parameters = parameters
self.__remappings = remappings
self.__parameters = [] if parameters is None else normalized_params
self.__remappings = [] if remappings is None else list(normalize_remap_rules(remappings))
self.__arguments = arguments
self.__traits = traits

Expand All @@ -135,7 +150,9 @@ def __init__(
@property
def node_name(self):
"""Getter for node_name."""
return self.__node_name
if self.__final_node_name is None:
raise RuntimeError("cannot access 'node_name' before executing action")
return self.__final_node_name

@property
def node_namespace(self):
Expand Down Expand Up @@ -177,13 +194,6 @@ def expanded_parameter_arguments(self):
"""Getter for expanded_parameter_arguments."""
return self.__expanded_parameter_arguments

@property
def final_node_name(self):
"""Getter for final_node_name."""
if self.__substitutions_performed == True:
return self.__final_node_name
return None

@property
def expanded_remappings(self):
"""Getter for expanded_remappings."""
Expand All @@ -206,13 +216,15 @@ def _create_params_file_from_dict(self, params):
def _get_parameter_rule(self, param: 'Parameter', context: LaunchContext):
name, value = param.evaluate(context)
return f'{name}:={yaml.dump(value)}'

def prepare(self, context: LaunchContext, executable: Executable) -> None:
try:
if self.__substitutions_performed:
# This function may have already been called by a subclass' `execute`, for example.
return
self.__substitutions_performed = True
cmd_ext = ['--ros-args'] # Prepend ros specific arguments with --ros-args flag
executable.cmd.extend([normalize_to_list_of_substitutions(x) for x in cmd_ext])
if self.__node_name is not None:
self.__expanded_node_name = perform_substitutions(
context, normalize_to_list_of_substitutions(self.__node_name))
Expand All @@ -227,8 +239,8 @@ def prepare(self, context: LaunchContext, executable: Executable) -> None:
prefix_namespace(base_ns, expanded_node_namespace))
if expanded_node_namespace is not None:
self.__expanded_node_namespace = expanded_node_namespace
cmd_extension = ['-r', LocalSubstitution("ros_specific_arguments['ns']")]
executable.cmd.extend([normalize_to_list_of_substitutions(x) for x in cmd_extension])
cmd_ext = ['-r', LocalSubstitution("ros_specific_arguments['ns']")]
executable.cmd.extend([normalize_to_list_of_substitutions(x) for x in cmd_ext])
validate_namespace(self.__expanded_node_namespace)
except Exception:
self.__logger.error(
Expand All @@ -249,8 +261,8 @@ def prepare(self, context: LaunchContext, executable: Executable) -> None:
if global_params is not None:
param_file_path = self._create_params_file_from_dict(global_params)
self.__expanded_parameter_arguments.append((param_file_path, True))
cmd_extension = ['--params-file', f'{param_file_path}']
executable.cmd.extend([normalize_to_list_of_substitutions(x) for x in cmd_extension])
cmd_ext = ['--params-file', f'{param_file_path}']
executable.cmd.extend([normalize_to_list_of_substitutions(x) for x in cmd_ext])
assert os.path.isfile(param_file_path)
# expand parameters too
if self.__parameters is not None:
Expand All @@ -274,8 +286,8 @@ def prepare(self, context: LaunchContext, executable: Executable) -> None:
)
continue
self.__expanded_parameter_arguments.append((param_argument, is_file))
cmd_extension = ['--params-file' if is_file else '-p', f'{param_argument}']
executable.cmd.extend([normalize_to_list_of_substitutions(x) for x in cmd_extension])
cmd_ext = ['--params-file' if is_file else '-p', f'{param_argument}']
executable.cmd.extend([normalize_to_list_of_substitutions(x) for x in cmd_ext])
# expand remappings too
global_remaps = context.launch_configurations.get('ros_remaps', None)
if global_remaps or self.__remappings:
Expand All @@ -288,7 +300,25 @@ def prepare(self, context: LaunchContext, executable: Executable) -> None:
for src, dst in self.__remappings
])
if self.__expanded_remappings:
cmd_extension = []
cmd_ext = []
for src, dst in self.__expanded_remappings:
cmd_extension.extend(['-r', f'{src}:={dst}'])
executable.cmd.extend([normalize_to_list_of_substitutions(x) for x in cmd_extension])
cmd_ext.extend(['-r', f'{src}:={dst}'])
executable.cmd.extend([normalize_to_list_of_substitutions(x) for x in cmd_ext])
# Prepare the ros_specific_arguments list and add it to the context so that the
# LocalSubstitution placeholders added to the the cmd can be expanded using the contents.
ros_specific_arguments: Dict[str, Union[str, List[str]]] = {}
if self.__node_name is not None:
ros_specific_arguments['name'] = '__node:={}'.format(self.__expanded_node_name)
if self.__expanded_node_namespace != '':
ros_specific_arguments['ns'] = '__ns:={}'.format(self.__expanded_node_namespace)
context.extend_locals({'ros_specific_arguments': ros_specific_arguments})

if self.is_node_name_fully_specified():
add_node_name(context, self.node_name)
node_name_count = get_node_name_count(context, self.node_name)
if node_name_count > 1:
execute_process_logger = launch.logging.get_logger(self.name)
execute_process_logger.warning(
'there are now at least {} nodes with the name {} created within this '
'launch context'.format(node_name_count, self.node_name)
)
3 changes: 2 additions & 1 deletion launch_ros/launch_ros/descriptions/node_trait.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
from launch import Action
from launch import LaunchContext


class NodeTrait:
"""Describes a trait of a node."""

Expand All @@ -40,4 +41,4 @@ def __init__(self) -> None:
pass

def prepare(self, node, context: LaunchContext, action: Action):
"""Performs any actions necessary to prepare the node for execution."""
"""Perform any actions necessary to prepare the node for execution."""
5 changes: 2 additions & 3 deletions launch_ros/launch_ros/descriptions/ros_executable.py
Original file line number Diff line number Diff line change
Expand Up @@ -33,8 +33,10 @@

from ..descriptions import Node


class RosExecutable(Executable):
"""Describes an executable with ROS features which may be run by the launch system."""

def __init__(
self, *,
executable: Optional[SomeSubstitutionsType] = None,
Expand All @@ -50,7 +52,6 @@ def __init__(
:param: package the package in which the node executable can be found
:param: nodes the ROS node(s) included in the executable
"""

if package is not None:
cmd = [ExecutableInPackage(package=package, executable=executable)]
else:
Expand Down Expand Up @@ -84,9 +85,7 @@ def apply_context(self, context: LaunchContext):
- prepares all nodes
- performs substitutions on various properties
"""

for node in self.__nodes:
node.prepare(context, self)

super().apply_context(context)

6 changes: 3 additions & 3 deletions test_launch_ros/test/test_launch_ros/actions/test_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,7 @@ def test_launch_node_with_remappings(self):
self._assert_launch_no_errors([node_action])

# Check the expanded parameters.
expanded_remappings = node_action._Node__expanded_remappings
expanded_remappings = node_action._Node__node_desc.expanded_remappings
assert len(expanded_remappings) == 2
for i in range(2):
assert expanded_remappings[i] == ('chatter', 'new_chatter')
Expand Down Expand Up @@ -176,7 +176,7 @@ def test_launch_node_with_parameter_descriptions(self):
)
self._assert_launch_no_errors([node_action])

expanded_parameter_arguments = node_action._Node__expanded_parameter_arguments
expanded_parameter_arguments = node_action._Node__node_desc.expanded_parameter_arguments
assert len(expanded_parameter_arguments) == 5
parameters = []
for item, is_file in expanded_parameter_arguments:
Expand Down Expand Up @@ -213,7 +213,7 @@ def test_launch_node_with_parameter_dict(self):
self._assert_launch_no_errors([node_action])

# Check the expanded parameters (will be written to a file).
expanded_parameter_arguments = node_action._Node__expanded_parameter_arguments
expanded_parameter_arguments = node_action._Node__node_desc.expanded_parameter_arguments
assert len(expanded_parameter_arguments) == 1
file_path, is_file = expanded_parameter_arguments[0]
assert is_file
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,10 +14,13 @@

"""Tests for the PushRosNamespace Action."""

from _collections import defaultdict

from launch_ros.actions import Node
from launch_ros.actions import PushRosNamespace
from launch_ros.actions.load_composable_nodes import get_composable_node_load_request
from launch_ros.descriptions import ComposableNode
from launch_ros.descriptions import Node as NodeDescription

import pytest

Expand All @@ -26,6 +29,14 @@ class MockContext:

def __init__(self):
self.launch_configurations = {}
self.locals = lambda: None
self.locals.unique_ros_node_names = defaultdict(int)

def extend_globals(self, val):
pass

def extend_locals(self, val):
pass

def perform_substitution(self, sub):
return sub.perform(None)
Expand Down Expand Up @@ -118,10 +129,11 @@ def test_push_ros_namespace(config):
)
node._perform_substitutions(lc)
expected_ns = (
config.expected_ns if config.expected_ns is not None else Node.UNSPECIFIED_NODE_NAMESPACE
config.expected_ns if config.expected_ns is not None else
NodeDescription.UNSPECIFIED_NODE_NAMESPACE
)
expected_name = (
config.node_name if config.node_name is not None else Node.UNSPECIFIED_NODE_NAME
config.node_name if config.node_name is not None else NodeDescription.UNSPECIFIED_NODE_NAME
)
expected_fqn = expected_ns.rstrip('/') + '/' + expected_name
assert expected_ns == node.expanded_node_namespace
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@

"""Tests for the SetParameter Action."""

from _collections import defaultdict

from launch import LaunchContext
from launch.actions import PopLaunchConfigurations
from launch.actions import PushLaunchConfigurations
Expand All @@ -33,6 +35,14 @@ class MockContext:

def __init__(self):
self.launch_configurations = {}
self.locals = lambda: None
self.locals.unique_ros_node_names = defaultdict(int)

def extend_globals(self, val):
pass

def extend_locals(self, val):
pass

def perform_substitution(self, sub):
return sub.perform(None)
Expand Down Expand Up @@ -112,7 +122,7 @@ def test_set_param_with_node():
set_param = SetParameter(name='my_param', value='my_value')
set_param.execute(lc)
node._perform_substitutions(lc)
expanded_parameter_arguments = node._Node__expanded_parameter_arguments
expanded_parameter_arguments = node._Node__node_desc.expanded_parameter_arguments
assert len(expanded_parameter_arguments) == 2
param_file_path, is_file = expanded_parameter_arguments[0]
assert is_file
Expand Down
Loading

0 comments on commit 56a5946

Please sign in to comment.