Skip to content

Commit

Permalink
[LifecycleNode] add bond_heartbeat_period (#4342)
Browse files Browse the repository at this point in the history
* add bond_heartbeat_period


Signed-off-by: Guillaume Doisy <guillaume@dexory.com>

* lint

Signed-off-by: Guillaume Doisy <guillaume@dexory.com>

---------

Signed-off-by: Guillaume Doisy <guillaume@dexory.com>
Co-authored-by: Guillaume Doisy <guillaume@dexory.com>
  • Loading branch information
doisyg and Guillaume Doisy committed May 14, 2024
1 parent 4fa12ac commit 2ae649b
Show file tree
Hide file tree
Showing 2 changed files with 21 additions and 11 deletions.
1 change: 1 addition & 0 deletions nav2_util/include/nav2_util/lifecycle_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -205,6 +205,7 @@ class LifecycleNode : public rclcpp_lifecycle::LifecycleNode

// Connection to tell that server is still up
std::unique_ptr<bond::Bond> bond_{nullptr};
double bond_heartbeat_period;
};

} // namespace nav2_util
Expand Down
31 changes: 20 additions & 11 deletions nav2_util/src/lifecycle_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#include <vector>

#include "lifecycle_msgs/msg/state.hpp"
#include "nav2_util/node_utils.hpp"

namespace nav2_util
{
Expand All @@ -35,6 +36,10 @@ LifecycleNode::LifecycleNode(
rclcpp::Parameter(
bond::msg::Constants::DISABLE_HEARTBEAT_TIMEOUT_PARAM, true));

nav2_util::declare_parameter_if_not_declared(
this, "bond_heartbeat_period", rclcpp::ParameterValue(0.1));
this->get_parameter("bond_heartbeat_period", bond_heartbeat_period);

printLifecycleNodeNotification();

register_rcl_preshutdown_callback();
Expand All @@ -55,16 +60,18 @@ LifecycleNode::~LifecycleNode()

void LifecycleNode::createBond()
{
RCLCPP_INFO(get_logger(), "Creating bond (%s) to lifecycle manager.", this->get_name());
if (bond_heartbeat_period > 0.0) {
RCLCPP_INFO(get_logger(), "Creating bond (%s) to lifecycle manager.", this->get_name());

bond_ = std::make_unique<bond::Bond>(
std::string("bond"),
this->get_name(),
shared_from_this());
bond_ = std::make_unique<bond::Bond>(
std::string("bond"),
this->get_name(),
shared_from_this());

bond_->setHeartbeatPeriod(0.10);
bond_->setHeartbeatTimeout(4.0);
bond_->start();
bond_->setHeartbeatPeriod(bond_heartbeat_period);
bond_->setHeartbeatTimeout(4.0);
bond_->start();
}
}

void LifecycleNode::runCleanups()
Expand Down Expand Up @@ -110,10 +117,12 @@ void LifecycleNode::register_rcl_preshutdown_callback()

void LifecycleNode::destroyBond()
{
RCLCPP_INFO(get_logger(), "Destroying bond (%s) to lifecycle manager.", this->get_name());
if (bond_heartbeat_period > 0.0) {
RCLCPP_INFO(get_logger(), "Destroying bond (%s) to lifecycle manager.", this->get_name());

if (bond_) {
bond_.reset();
if (bond_) {
bond_.reset();
}
}
}

Expand Down

0 comments on commit 2ae649b

Please sign in to comment.