Skip to content

Declaring static type paramaters no longer matches rclcpp functionaility and always raises an exception #1460

@gstorer

Description

@gstorer

Operating System:

Ubuntu 24

ROS version or commit hash:

Jazzy

Client library (if applicable):

rclpy

Steps to reproduce issue

I have noticed this issue when upgrading our code base from Humble to Jazzy.

When declaring a static typed parameter in rclpy, it is no longer possible to supply a value at run time, a default value must be specified.

The following code runs fine in Humble but raises an exception in Jazzy when called as follows:
python3 test_node.py --ros-args --param my_string_param:=test_value

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


class SimpleParameterNode(Node):
    def __init__(self):
        super().__init__('simple_parameter_node')
        
        # Declare a string parameter without a default value using a descriptor to set its type
        string_descriptor = ParameterDescriptor(
            type=ParameterType.PARAMETER_STRING,
            description='A required string parameter'
        )
    
        self.my_param = self.declare_parameter(
            'my_string_param',
            descriptor=string_descriptor
        )
            
        # Print the parameter value
        self.get_logger().info(f'Received parameter: {repr(self.my_param.value)}')

def main(args=None):
    rclpy.init(args=args)
    node = SimpleParameterNode()
    
    try:
        rclpy.spin(node)
    except KeyboardInterrupt:
        pass
    finally:
        node.destroy_node()
        rclpy.shutdown()


if __name__ == '__main__':
    main()

The exception raised is:
ValueError: Cannot declare a statically typed parameter with default value of type PARAMETER_NOT_SET

Expected behavior

The behavior should match rclcpp. If a static typed parameter is declared without a default, it must be supplied when running the node or an exception is raised.

Actual behavior

rclpy always raises an exception for a static parameter without a default, even if it is supplied at runtime.

Additional information

This appears to be the pull request were the issue was introduced: #1216 . In it @haianos correctly identifies some user stories where it will be an issue. Note that before this pull request rclpy behavior didn't match rclcpp either, instead it never raised an exception. However, this didn't prevent my code from working.

For an example of the use of static typed parameters without defaults from within the ros2 org (in C++) see: https://github.com/ros2/openrobotics_darknet_ros/blob/6c741578d55b19ffb9a120b79cb8a78c7b60fbd6/src/detector_node.cpp#L98

Metadata

Metadata

Assignees

Labels

bugSomething isn't working

Type

No type

Projects

No projects

Milestone

No milestone

Relationships

None yet

Development

No branches or pull requests

Issue actions