From 8ffcf5330480f29e77568169e3b6c8e00b2919bc Mon Sep 17 00:00:00 2001 From: Zheng Qu Date: Fri, 31 Oct 2025 20:50:53 +0100 Subject: [PATCH 1/2] feat(lifecycle_node): add get_parameter_or overload returning value or alternative Signed-off-by: Zheng Qu --- .../include/rclcpp_lifecycle/lifecycle_node.hpp | 10 ++++++++++ .../include/rclcpp_lifecycle/lifecycle_node_impl.hpp | 11 +++++++++++ 2 files changed, 21 insertions(+) diff --git a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp index 6e196c887b..d91a11d6ab 100644 --- a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp +++ b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp @@ -486,6 +486,16 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, ParameterT & value, const ParameterT & alternative_value) const; + /// Return the parameter value, or the "alternative_value" if not set. + /** + * \sa rclcpp::Node::get_parameter_or + */ + template + ParameterT + get_parameter_or( + const std::string & name, + const ParameterT & alternative_value) const; + /// Return the parameters by the given parameter names. /** * \sa rclcpp::Node::get_parameters diff --git a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node_impl.hpp b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node_impl.hpp index b1e73b6c64..059d722a24 100644 --- a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node_impl.hpp +++ b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node_impl.hpp @@ -306,5 +306,16 @@ LifecycleNode::get_parameter_or( return got_parameter; } +template +ParameterT +LifecycleNode::get_parameter_or( + const std::string & name, + const ParameterT & alternative_value) const +{ + ParameterT parameter; + get_parameter_or(name, parameter, alternative_value); + return parameter; +} + } // namespace rclcpp_lifecycle #endif // RCLCPP_LIFECYCLE__LIFECYCLE_NODE_IMPL_HPP_ From 384c7819d9a5efb5c1bd429e361a27e23198af53 Mon Sep 17 00:00:00 2001 From: Zheng Qu Date: Sat, 1 Nov 2025 07:45:39 +0100 Subject: [PATCH 2/2] test: add tests for get_parameter_or in lifecycle node Signed-off-by: Zheng Qu --- rclcpp_lifecycle/test/test_lifecycle_node.cpp | 20 +++++++++++++++++++ 1 file changed, 20 insertions(+) diff --git a/rclcpp_lifecycle/test/test_lifecycle_node.cpp b/rclcpp_lifecycle/test/test_lifecycle_node.cpp index c31d408a71..e6edb2ea3f 100644 --- a/rclcpp_lifecycle/test/test_lifecycle_node.cpp +++ b/rclcpp_lifecycle/test/test_lifecycle_node.cpp @@ -840,6 +840,26 @@ TEST_F(TestDefaultStateMachine, check_parameters) { EXPECT_TRUE(parameter.as_bool()); } +TEST_F(TestDefaultStateMachine, test_get_parameter_or) { + auto test_node = std::make_shared("testnode"); + + const std::string param_name = "test_param"; + int param_int = -999; + + // Parameter does not exist, should return "or" value + EXPECT_FALSE(test_node->get_parameter_or(param_name, param_int, 123)); + EXPECT_EQ(param_int, 123); + EXPECT_EQ(test_node->get_parameter_or(param_name, 456), 456); + + // Declare param_int + test_node->declare_parameter(param_name, rclcpp::ParameterValue(789)); + + // Parameter exists, should return existing value + EXPECT_TRUE(test_node->get_parameter_or(param_name, param_int, 123)); + EXPECT_EQ(param_int, 789); + EXPECT_EQ(test_node->get_parameter_or(param_name, 456), 789); +} + TEST_F(TestDefaultStateMachine, test_getters) { auto test_node = std::make_shared("testnode"); auto options = test_node->get_node_options();