Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

memory safe subscription callback #108

Draft
wants to merge 7 commits into
base: ros2
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 4 additions & 1 deletion bondcpp/include/bondcpp/bond.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ namespace bond
* another process and be notified when it dies. In turn, it will be
* notified when you die.
*/
class Bond
class Bond : public std::enable_shared_from_this<Bond>
{
public:
using EventCallback = std::function<void (void)>;
Expand Down Expand Up @@ -239,7 +239,9 @@ class Bond

rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_;
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_;
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_params_;
rclcpp::node_interfaces::NodeTimersInterface::SharedPtr node_timers_;
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_;

rclcpp::TimerBase::SharedPtr connect_timer_;
rclcpp::TimerBase::SharedPtr disconnect_timer_;
Expand Down Expand Up @@ -274,6 +276,7 @@ class Bond
rclcpp::Duration heartbeat_period_;
rclcpp::Duration dead_publish_period_;

rclcpp::CallbackGroup::SharedPtr sub_callback_group_;
rclcpp::Subscription<bond::msg::Status>::SharedPtr sub_;
rclcpp::Publisher<bond::msg::Status>::SharedPtr pub_;
};
Expand Down
54 changes: 54 additions & 0 deletions bondcpp/include/bondcpp/createSafeCallback.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,54 @@
// Copyright (c) 2009, Willow Garage, Inc. All rights reserved.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
//
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
//
// * Neither the name of the Willow Garage nor the names of its
// contributors may be used to endorse or promote products derived from
// this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.

/** \author Mike Wake */
#ifndef BONDCPP__CREATESAFECALLBACK_HPP_
#define BONDCPP__CREATESAFECALLBACK_HPP_

#include <memory>
#include <type_traits>

// Expects obj to inhert from std::enable_shared_from_this
template<typename T, typename MessageT>
auto createSafeSubscriptionMemFuncCallback(
std::shared_ptr<T> obj,
void (T::* memberFunc)(const MessageT &))
{
static_assert(
std::is_base_of_v<std::enable_shared_from_this<T>, T>,
"Type expected to inherit from std::enable_shared_from_this");

std::weak_ptr<T> weak_obj = obj;
return [weak_obj, memberFunc](const MessageT & msg) {
if (auto shared_obj = weak_obj.lock()) {
((*shared_obj).*memberFunc)(msg);
}
};
}

#endif // BONDCPP__CREATESAFECALLBACK_HPP_
57 changes: 37 additions & 20 deletions bondcpp/src/bond.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@
// Author: Stuart Glaser

#include <bondcpp/bond.hpp>
#include <bondcpp/createSafeCallback.hpp>

#ifdef _WIN32
#include <Rpc.h>
Expand Down Expand Up @@ -81,7 +82,9 @@ Bond::Bond(
EventCallback on_formed)
: node_base_(node_base),
node_logging_(node_logging),
node_params_(node_params),
node_timers_(node_timers),
node_topics_(node_topics),
bondsm_(std::make_unique<BondSM>(this)),
sm_(*bondsm_),
topic_(topic),
Expand All @@ -100,29 +103,22 @@ Bond::Bond(
dead_publish_period_(
rclcpp::Duration::from_seconds(bond::msg::Constants::DEAD_PUBLISH_PERIOD))
{
if (!node_params->has_parameter(bond::msg::Constants::DISABLE_HEARTBEAT_TIMEOUT_PARAM)) {
node_params->declare_parameter(
if (!node_params_->has_parameter(bond::msg::Constants::DISABLE_HEARTBEAT_TIMEOUT_PARAM)) {
node_params_->declare_parameter(
bond::msg::Constants::DISABLE_HEARTBEAT_TIMEOUT_PARAM,
rclcpp::ParameterValue(false));
}

disable_heartbeat_timeout_ =
node_params->get_parameter(bond::msg::Constants::DISABLE_HEARTBEAT_TIMEOUT_PARAM).as_bool();
node_params_->get_parameter(bond::msg::Constants::DISABLE_HEARTBEAT_TIMEOUT_PARAM).as_bool();

setupConnections();

pub_ = rclcpp::create_publisher<bond::msg::Status>(
node_params,
node_topics,
node_params_,
node_topics_,
topic_,
rclcpp::QoS(rclcpp::KeepLast(5)));

sub_ = rclcpp::create_subscription<bond::msg::Status>(
node_params,
node_topics,
topic_,
rclcpp::QoS(100),
std::bind(&Bond::bondStatusCB, this, std::placeholders::_1));
}

Bond::Bond(
Expand Down Expand Up @@ -364,6 +360,26 @@ void Bond::deadpublishingTimerCancel()

void Bond::start()
{
// create_subscription must be done outside of constructor
// to allow usage of shared_from_this()

// TBD: Should recreation of subscription be prevented?
if (!started_) {
sub_ = rclcpp::create_subscription<bond::msg::Status>(
node_params_,
node_topics_,
topic_,
rclcpp::QoS(100),
createSafeSubscriptionMemFuncCallback(
shared_from_this(),
&Bond::bondStatusCB)
);
} else {
RCLCPP_WARN(
node_logging_->get_logger(),
"start() already started skipping subscription recreation");
}

connect_timer_reset_flag_ = true;
connectTimerReset();
publishingTimerReset();
Expand Down Expand Up @@ -550,16 +566,17 @@ void Bond::doPublishing()

void Bond::publishStatus(bool active)
{
bond::msg::Status msg;
auto msg = std::make_unique<bond::msg::Status>();
rclcpp::Clock steady_clock(RCL_STEADY_TIME);
rclcpp::Time now = steady_clock.now();
msg.header.stamp = now;
msg.id = id_;
msg.instance_id = instance_id_;
msg.active = active;
msg.heartbeat_timeout = static_cast<float>(heartbeat_timeout_.seconds());
msg.heartbeat_period = static_cast<float>(heartbeat_period_.seconds());
pub_->publish(msg);
msg->header.stamp = now;
msg->id = id_;
msg->instance_id = instance_id_;
msg->active = active;
msg->heartbeat_timeout = static_cast<float>(heartbeat_timeout_.seconds());
msg->heartbeat_period = static_cast<float>(heartbeat_period_.seconds());
if (pub_->get_subscription_count() < 1) {return;}
pub_->publish(std::move(msg));
Copy link
Author

@ewak ewak Jan 25, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@SteveMacenski This is another use_intraprocess_comms fix. i.e the Bond Status publisher for use_intraprocess_comms should use a unique msg and check for subscribers.

This allows nav2_system_tests to pass.

NOTE: without this change the following test was failure was very reproducible for me.

colcon test --packages-select nav2_system_tests --event-handlers=console_direct+ --ctest-args -R test_speed_filter_global

ref: ros-navigation/navigation2#4691

Copy link
Member

@SteveMacenski SteveMacenski Jan 28, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Does this make it pass because of the if (pub_->get_subscription_count() < 1) {return;} return condition or the unique_ptr publisher? I'm curious if this is pattern I should be on the look-out for on MsgT publishers for depedencies, or if this is a special case where we can get around it by skipping publication.

Though this fixes the issue in Bond, if its the latter, I think that should be reported in the rclcpp thread that publishing IPC message instances causes part of the issue. That means something in the publish() for MsgT signatures is broken whereas MsgT::UniquePtr are not (which hopefully would be an easy apples-to-apples fix).

}

void Bond::flushPendingCallbacks()
Expand Down
24 changes: 12 additions & 12 deletions test_bond/test/test_callbacks_cpp.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -83,15 +83,15 @@ TEST_F(TestCallbacksCpp, dieInLifeCallback)
{
auto nh1 = rclcpp::Node::make_shared("test_callbacks_cpp");
std::string id1 = genId();
bond::Bond a(TOPIC, id1, nh1);
bond::Bond b(TOPIC, id1, nh1);
auto a = std::make_shared<bond::Bond>(TOPIC, id1, nh1);
auto b = std::make_shared<bond::Bond>(TOPIC, id1, nh1);

a.setFormedCallback(
a->setFormedCallback(
[&a]() {
a.breakBond();
a->breakBond();
});
a.start();
b.start();
a->start();
b->start();

std::atomic<bool> isRunning {true};
auto runThread = std::thread(
Expand All @@ -101,8 +101,8 @@ TEST_F(TestCallbacksCpp, dieInLifeCallback)
}
});

EXPECT_TRUE(a.waitUntilFormed(rclcpp::Duration(5.0s)));
EXPECT_TRUE(b.waitUntilBroken(rclcpp::Duration(3.0s)));
EXPECT_TRUE(a->waitUntilFormed(rclcpp::Duration(5.0s)));
EXPECT_TRUE(b->waitUntilBroken(rclcpp::Duration(3.0s)));

isRunning = false;
runThread.join();
Expand All @@ -112,9 +112,9 @@ TEST_F(TestCallbacksCpp, remoteNeverConnects)
{
auto nh2 = rclcpp::Node::make_shared("test_callbacks_cpp_2");
std::string id2 = genId();
bond::Bond a1(TOPIC, id2, nh2);
auto a1 = std::make_shared<bond::Bond>(TOPIC, id2, nh2);

a1.start();
a1->start();

std::atomic<bool> isRunning {true};
auto runThread = std::thread(
Expand All @@ -124,8 +124,8 @@ TEST_F(TestCallbacksCpp, remoteNeverConnects)
}
});

EXPECT_FALSE(a1.waitUntilFormed(rclcpp::Duration(4.0s)));
EXPECT_TRUE(a1.waitUntilBroken(rclcpp::Duration(10.0s)));
EXPECT_FALSE(a1->waitUntilFormed(rclcpp::Duration(4.0s)));
EXPECT_TRUE(a1->waitUntilBroken(rclcpp::Duration(10.0s)));

isRunning = false;
runThread.join();
Expand Down