From 85c7baa82afc0442c716f185218c808792a34436 Mon Sep 17 00:00:00 2001 From: Sanjeev Kumar Date: Sun, 1 Sep 2024 12:06:57 +0200 Subject: [PATCH] Fix deprecation warning in paramater declaration Updated the paramater declaration in `publisher_forward_position_controller` to resolve a deprecation warning. Changes Made: - Replaced `self.declare_parameter(name)` with `self.declare_parameter(name, descriptor=ParameterDescriptor(dynamic_typing=True))` Fixes: #1239 --- .../publisher_forward_position_controller.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/ros2_controllers_test_nodes/ros2_controllers_test_nodes/publisher_forward_position_controller.py b/ros2_controllers_test_nodes/ros2_controllers_test_nodes/publisher_forward_position_controller.py index 5cf28ac604..2d0cb3bb77 100644 --- a/ros2_controllers_test_nodes/ros2_controllers_test_nodes/publisher_forward_position_controller.py +++ b/ros2_controllers_test_nodes/ros2_controllers_test_nodes/publisher_forward_position_controller.py @@ -17,6 +17,7 @@ import rclpy from rclpy.node import Node +from rcl_interfaces.msg import ParameterDescriptor from std_msgs.msg import Float64MultiArray @@ -37,7 +38,7 @@ def __init__(self): # Read all positions from parameters self.goals = [] for name in goal_names: - self.declare_parameter(name) + self.declare_parameter(name, descriptor=ParameterDescriptor(dynamic_typing=True)) goal = self.get_parameter(name).value if goal is None or len(goal) == 0: raise Exception(f'Values for goal "{name}" not set!')