From 35bb5f7c2eff9ec82175db1e8e5fcb8a60b094e2 Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Wed, 6 Mar 2024 08:45:36 +0100 Subject: [PATCH] add conditioning to get_parameter_value method import (#1428) --- controller_manager/controller_manager/spawner.py | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/controller_manager/controller_manager/spawner.py b/controller_manager/controller_manager/spawner.py index cf78442856..1d11d80fe1 100644 --- a/controller_manager/controller_manager/spawner.py +++ b/controller_manager/controller_manager/spawner.py @@ -32,7 +32,13 @@ from rcl_interfaces.msg import Parameter from rclpy.duration import Duration from rclpy.node import Node -from rclpy.parameter import get_parameter_value + +# @note: The versions conditioning is added here to support the source-compatibility with Humble +# The `get_parameter_value` function is moved to `rclpy.parameter` module from `ros2param.api` module from version 3.6.0 +try: + from rclpy.parameter import get_parameter_value +except ImportError: + from ros2param.api import get_parameter_value from rclpy.signals import SignalHandlerOptions from ros2param.api import call_set_parameters