Skip to content

Commit 3bed8ed

Browse files
Add support for enable_lifecycle_services parameter using nav2 utilities
Expose the enable_communication_interface parameter from rclcpp_lifecycle::LifecycleNode through nav2's LifecycleNode wrapper using proper nav2 utilities: - Use nav2::declare_parameter_if_not_declared() with default value true - Use get_parameter() for value retrieval - Create temporary node in static helper to properly access nav2 utilities - Declare parameter in constructor body for future use This allows users to disable lifecycle communication interfaces when manually managing node lifecycle transitions by setting the parameter via: - NodeOptions parameter overrides - ROS parameter files - Launch file parameters Fixes #5305 Co-authored-by: Steve Macenski <[email protected]>
1 parent ce87527 commit 3bed8ed

File tree

1 file changed

+26
-1
lines changed

1 file changed

+26
-1
lines changed

nav2_ros_common/include/nav2_ros_common/lifecycle_node.hpp

Lines changed: 26 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -59,7 +59,7 @@ class LifecycleNode : public rclcpp_lifecycle::LifecycleNode
5959
const std::string & node_name,
6060
const std::string & ns,
6161
const rclcpp::NodeOptions & options = rclcpp::NodeOptions())
62-
: rclcpp_lifecycle::LifecycleNode(node_name, ns, options)
62+
: rclcpp_lifecycle::LifecycleNode(node_name, ns, options, getEnableLifecycleServices(options))
6363
{
6464
// server side never times out from lifecycle manager
6565
this->declare_parameter(bond::msg::Constants::DISABLE_HEARTBEAT_TIMEOUT_PARAM, true);
@@ -79,6 +79,10 @@ class LifecycleNode : public rclcpp_lifecycle::LifecycleNode
7979
autostart();
8080
}
8181

82+
// Declare the enable_lifecycle_services parameter for future use
83+
nav2::declare_parameter_if_not_declared(
84+
this, "enable_lifecycle_services", rclcpp::ParameterValue(true));
85+
8286
printLifecycleNodeNotification();
8387

8488
register_rcl_preshutdown_callback();
@@ -338,6 +342,27 @@ class LifecycleNode : public rclcpp_lifecycle::LifecycleNode
338342
}
339343
}
340344

345+
private:
346+
/**
347+
* @brief Get the enable_lifecycle_services parameter using nav2 utilities
348+
* @param options NodeOptions to use for creating temporary node
349+
* @return bool value for enable_lifecycle_services parameter (default: true)
350+
*/
351+
static bool getEnableLifecycleServices(const rclcpp::NodeOptions & options)
352+
{
353+
// Create a temporary node to properly declare and get the parameter
354+
auto temp_node = rclcpp::Node::make_shared("temp_lifecycle_param_node", options);
355+
356+
// Use nav2 utilities to declare and get the parameter
357+
nav2::declare_parameter_if_not_declared(
358+
temp_node, "enable_lifecycle_services", rclcpp::ParameterValue(true));
359+
360+
bool enable_lifecycle_services = true;
361+
temp_node->get_parameter("enable_lifecycle_services", enable_lifecycle_services);
362+
363+
return enable_lifecycle_services;
364+
}
365+
341366
protected:
342367
/**
343368
* @brief Print notifications for lifecycle node

0 commit comments

Comments
 (0)