ros2/launch_ros

String parameter with digits and `E` or `e` (e.g. "123E5") is always interpreted as double

chrmel opened this issue · 1 comments

chrmel commented

Bug report

When launching a ROS2 node with ros2 launch ... a parameter containing digits and E or e is always interpreted as a double value. Even when the parameter is defined as a string parameter and even when the whole parameter is passed as string.

  • Operating System:
    • Ubuntu 22.04
  • Installation type:
    • binaries
  • Version or commit hash:
    • humble
  • Client library (if applicable):
    • rclpy

Steps to reproduce issue

Create a Python package and have a simple node and launchfile
param_test.py

import signal
import rclpy

from rclpy.node import Node
from rcl_interfaces.msg import ParameterType


class ParamTest(Node):
    def __init__(self):
        Node.__init__(self, 'param_test')

        # parameter declaration and info
        self._param = self.declare_parameter('param', 'abc').get_parameter_value().string_value
        self.get_logger().info(f'String Param: {self._param}')


def main(args=None):
    def raise_keyboard_int(_, __):
        rclpy.logging.get_logger('param_test_node').info('stopping')
        raise KeyboardInterrupt()

    signal.signal(signal.SIGINT, raise_keyboard_int)

    rclpy.init(args=args)
    node = ParamTest()

    try:
        rclpy.spin_once(node)

    except KeyboardInterrupt:
        pass

    finally:
        node.destroy_node()



if __name__ == '__main__':
    main()

test.launch.py

#!/usr/bin/python3

from launch import LaunchDescription
from launch_ros.actions import Node
from launch.actions import DeclareLaunchArgument
from launch.substitutions import TextSubstitution, LaunchConfiguration


def generate_launch_description():
    return LaunchDescription([
        DeclareLaunchArgument(
            'param',
            default_value=TextSubstitution(text='abc'),
            description='String param'
        ),
        Node(
            package='param_test',
            executable='param_test',
            name='mccdaq_daq',
            output='screen',
            emulate_tty=True,
            parameters=[{
                'param': LaunchConfiguration('param'),
            }],
        ),
        ])

Expected behavior

$ ros2 launch param_test test.launch.py param:="123E5"
[INFO] [1697811050.937763500] [param_test]: String Param: 123E5

Actual behavior

$ ros2 launch param_test test.launch.py param:="123E5"
[INFO] [launch]: All log files can be found below /root/.ros/log/2023-10-20-14-11-17-221115-708631e4d2d9-2422
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [param_test-1]: process started with pid [2423]
[param_test-1] Traceback (most recent call last):
[param_test-1]   File "/ros2_ws/install/param_test/lib/param_test/param_test", line 33, in <module>
[param_test-1]     sys.exit(load_entry_point('param-test==0.0.0', 'console_scripts', 'param_test')())
[param_test-1]   File "/ros2_ws/install/param_test/lib/python3.10/site-packages/param_test/param_test.py", line 25, in main
[param_test-1]     node = ParamTest()
[param_test-1]   File "/ros2_ws/install/param_test/lib/python3.10/site-packages/param_test/param_test.py", line 13, in __init__
[param_test-1]     self._param = self.declare_parameter('param', 'abc').get_parameter_value().string_value
[param_test-1]   File "/opt/ros/humble/local/lib/python3.10/dist-packages/rclpy/node.py", line 367, in declare_parameter
[param_test-1]     return self.declare_parameters('', [args], ignore_override)[0]
[param_test-1]   File "/opt/ros/humble/local/lib/python3.10/dist-packages/rclpy/node.py", line 494, in declare_parameters
[param_test-1]     self._set_parameters(
[param_test-1]   File "/opt/ros/humble/local/lib/python3.10/dist-packages/rclpy/node.py", line 739, in _set_parameters
[param_test-1]     raise InvalidParameterTypeException(
[param_test-1] rclpy.exceptions.InvalidParameterTypeException: Trying to set parameter 'param' to '12300000.0' of type 'DOUBLE', expecting type 'STRING'

Additional information

Mirght be related to ros2/ros2cli#677?

  • ros2 run ... can be forced to interpret the parameter as a string:
    $ ros2 run param_test param_test --ros-args -p "param:='123E5'"
    [INFO] [1697811050.937763500] [param_test]: String Param: 123E5
  • ros2 launch ... cannot be forced to take this parameter as a string:
    $ ros2 launch param_test test.launch.py param:="123E5"
    ... rclpy.exceptions.InvalidParameterTypeException: Trying to set parameter 'param' to '12300000.0' of type 'DOUBLE', expecting type 'STRING'
    $ ros2 launch param_test test.launch.py param:="'123E5'"
    ... rclpy.exceptions.InvalidParameterTypeException: Trying to set parameter 'param' to '12300000.0' of type 'DOUBLE', expecting type 'STRING'
    $ ros2 launch param_test test.launch.py param:='"123E5"'
    ... rclpy.exceptions.InvalidParameterTypeException: Trying to set parameter 'param' to '12300000.0' of type 'DOUBLE', expecting type 'STRING'
    And the most interesting one:
    $ ros2 launch param_test test.launch.py param:='!!str 123E5'
    ... rclpy.exceptions.InvalidParameterTypeException: Trying to set parameter 'param' to '12300000.0' of type 'DOUBLE', expecting type 'STRING'
    Even using all kinds of escapes, ASCII codes and what ever did not work!

I think this problem is related to https://github.com/ros2/launch_ros/tree/rolling/ros2launch, not in here ros2cli. (probably https://github.com/ros2/launch/tree/rolling/launch.)

@clalancette can you move this issue to https://github.com/ros2/launch_ros?

note: this problem is reproducible with ros2/ros2@1f5bd8e current head today.