Skip to content

Commit

Permalink
add conditioning to get_parameter_value method import (#1428)
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor authored Mar 6, 2024
1 parent d0071c0 commit 35bb5f7
Showing 1 changed file with 7 additions and 1 deletion.
8 changes: 7 additions & 1 deletion controller_manager/controller_manager/spawner.py
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down

0 comments on commit 35bb5f7

Please sign in to comment.