Skip to content

Commit 7f4a016

Browse files
committed
creating auto-transition option for nav2_util::LifecycleNode (#4804)
Signed-off-by: Steve Macenski <stevenmacenski@gmail.com>
1 parent c65b891 commit 7f4a016

File tree

3 files changed

+79
-0
lines changed

3 files changed

+79
-0
lines changed

nav2_util/include/nav2_util/lifecycle_node.hpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -168,6 +168,11 @@ class LifecycleNode : public rclcpp_lifecycle::LifecycleNode
168168
return nav2_util::CallbackReturn::SUCCESS;
169169
}
170170

171+
/**
172+
* @brief Automatically configure and active the node
173+
*/
174+
void autostart();
175+
171176
/**
172177
* @brief Perform preshutdown activities before our Context is shutdown.
173178
* Note that this is related to our Context's shutdown sequence, not the
@@ -207,6 +212,7 @@ class LifecycleNode : public rclcpp_lifecycle::LifecycleNode
207212
// Connection to tell that server is still up
208213
std::unique_ptr<bond::Bond> bond_{nullptr};
209214
double bond_heartbeat_period;
215+
rclcpp::TimerBase::SharedPtr autostart_timer_;
210216
};
211217

212218
} // namespace nav2_util

nav2_util/src/lifecycle_node.cpp

Lines changed: 28 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,8 @@
2121
#include "lifecycle_msgs/msg/state.hpp"
2222
#include "nav2_util/node_utils.hpp"
2323

24+
using namespace std::chrono_literals;
25+
2426
namespace nav2_util
2527
{
2628

@@ -40,6 +42,14 @@ LifecycleNode::LifecycleNode(
4042
this, "bond_heartbeat_period", rclcpp::ParameterValue(0.1));
4143
this->get_parameter("bond_heartbeat_period", bond_heartbeat_period);
4244

45+
bool autostart_node = false;
46+
nav2_util::declare_parameter_if_not_declared(
47+
this, "autostart_node", rclcpp::ParameterValue(false));
48+
this->get_parameter("autostart_node", autostart_node);
49+
if (autostart_node) {
50+
autostart();
51+
}
52+
4353
printLifecycleNodeNotification();
4454

4555
register_rcl_preshutdown_callback();
@@ -74,6 +84,24 @@ void LifecycleNode::createBond()
7484
}
7585
}
7686

87+
void LifecycleNode::autostart()
88+
{
89+
using lifecycle_msgs::msg::State;
90+
autostart_timer_ = this->create_wall_timer(
91+
0s,
92+
[this]() -> void {
93+
autostart_timer_->cancel();
94+
RCLCPP_INFO(get_logger(), "Auto-starting node: %s", this->get_name());
95+
if (configure().id() != State::PRIMARY_STATE_INACTIVE) {
96+
RCLCPP_ERROR(get_logger(), "Auto-starting node %s failed to configure!", this->get_name());
97+
return;
98+
}
99+
if (activate().id() != State::PRIMARY_STATE_ACTIVE) {
100+
RCLCPP_ERROR(get_logger(), "Auto-starting node %s failed to activate!", this->get_name());
101+
}
102+
});
103+
}
104+
77105
void LifecycleNode::runCleanups()
78106
{
79107
/*

nav2_util/test/test_lifecycle_node.cpp

Lines changed: 45 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -26,6 +26,27 @@ class RclCppFixture
2626
};
2727
RclCppFixture g_rclcppfixture;
2828

29+
class LifecycleTransitionTestNode : public nav2_util::LifecycleNode
30+
{
31+
public:
32+
explicit LifecycleTransitionTestNode(rclcpp::NodeOptions options)
33+
: nav2_util::LifecycleNode("test_node", "", options) {}
34+
35+
nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State &) override
36+
{
37+
configured = true;
38+
return nav2_util::CallbackReturn::SUCCESS;
39+
}
40+
nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &) override
41+
{
42+
activated = true;
43+
return nav2_util::CallbackReturn::SUCCESS;
44+
}
45+
46+
bool configured{false};
47+
bool activated{false};
48+
};
49+
2950
// For the following two tests, if the LifecycleNode doesn't shut down properly,
3051
// the overall test will hang since the rclcpp thread will still be running,
3152
// preventing the executable from exiting (the test will hang)
@@ -48,6 +69,30 @@ TEST(LifecycleNode, MultipleRclcppNodesExitCleanly)
4869
SUCCEED();
4970
}
5071

72+
TEST(LifecycleNode, AutostartTransitions)
73+
{
74+
auto executor = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
75+
rclcpp::NodeOptions options;
76+
auto node = std::make_shared<LifecycleTransitionTestNode>(options);
77+
executor->add_node(node->get_node_base_interface());
78+
executor->spin_some();
79+
EXPECT_FALSE(node->configured);
80+
EXPECT_FALSE(node->activated);
81+
executor.reset();
82+
node.reset();
83+
84+
85+
executor = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
86+
options.parameter_overrides({{"autostart_node", true}});
87+
node = std::make_shared<LifecycleTransitionTestNode>(options);
88+
executor->add_node(node->get_node_base_interface());
89+
executor->spin_some();
90+
EXPECT_TRUE(node->configured);
91+
EXPECT_TRUE(node->activated);
92+
executor.reset();
93+
node.reset();
94+
}
95+
5196
TEST(LifecycleNode, OnPreshutdownCbFires)
5297
{
5398
// Ensure the on_rcl_preshutdown_cb fires

0 commit comments

Comments
 (0)