Skip to content
Merged
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
16 changes: 12 additions & 4 deletions rclcpp/include/rclcpp/wait_result.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -176,7 +176,9 @@ class WaitResult final
for (; ii < wait_set.size_of_timers(); ++ii) {
if (rcl_wait_set.timers[ii] != nullptr) {
ret = wait_set.timers(ii);
break;
if (ret) {
break;
}
}
}
}
Expand Down Expand Up @@ -217,7 +219,9 @@ class WaitResult final
if (rcl_wait_set.subscriptions[ii] != nullptr) {
ret = wait_set.subscriptions(ii);
rcl_wait_set.subscriptions[ii] = nullptr;
break;
if (ret) {
break;
}
}
}
}
Expand All @@ -237,7 +241,9 @@ class WaitResult final
if (rcl_wait_set.services[ii] != nullptr) {
ret = wait_set.services(ii);
rcl_wait_set.services[ii] = nullptr;
break;
if (ret) {
break;
}
}
}
}
Expand All @@ -257,7 +263,9 @@ class WaitResult final
if (rcl_wait_set.clients[ii] != nullptr) {
ret = wait_set.clients(ii);
rcl_wait_set.clients[ii] = nullptr;
break;
if (ret) {
break;
}
}
}
}
Expand Down
21 changes: 11 additions & 10 deletions rclcpp/include/rclcpp/wait_set_policies/dynamic_storage.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -460,59 +460,60 @@ class DynamicStorage : public rclcpp::wait_set_policies::detail::StoragePolicyCo

size_t size_of_subscriptions() const
{
return shared_subscriptions_.size();
return subscriptions_.size();
}

size_t size_of_timers() const
{
return shared_timers_.size();
return timers_.size();
}

size_t size_of_clients() const
{
return shared_clients_.size();
return clients_.size();
}

size_t size_of_services() const
{
return shared_services_.size();
return services_.size();
}

size_t size_of_waitables() const
{
return shared_waitables_.size();
return waitables_.size();
}

std::shared_ptr<rclcpp::SubscriptionBase>
subscriptions(size_t ii) const
{
return shared_subscriptions_[ii].subscription;
return subscriptions_[ii].lock();
}

std::shared_ptr<rclcpp::TimerBase>
timers(size_t ii) const
{
return shared_timers_[ii];
return timers_[ii].lock();
}

std::shared_ptr<rclcpp::ClientBase>
clients(size_t ii) const
{
return shared_clients_[ii];
return clients_[ii].lock();
}

std::shared_ptr<rclcpp::ServiceBase>
services(size_t ii) const
{
return shared_services_[ii];
return services_[ii].lock();
}

std::shared_ptr<rclcpp::Waitable>
waitables(size_t ii) const
{
return shared_waitables_[ii].waitable;
return waitables_[ii].lock();
}

private:
size_t ownership_reference_counter_ = 0;

SequenceOfWeakSubscriptions subscriptions_;
Expand Down
4 changes: 0 additions & 4 deletions rclcpp/include/rclcpp/wait_set_template.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -734,8 +734,6 @@ class WaitSetTemplate final : private SynchronizationPolicy, private StoragePoli
wait_result_dirty_ = false;
// this method comes from the SynchronizationPolicy
this->sync_wait_result_acquire();
// this method comes from the StoragePolicy
this->storage_acquire_ownerships();
}

/// Called by the WaitResult's destructor to release resources.
Expand All @@ -752,8 +750,6 @@ class WaitSetTemplate final : private SynchronizationPolicy, private StoragePoli
}
wait_result_holding_ = false;
wait_result_dirty_ = false;
// this method comes from the StoragePolicy
this->storage_release_ownerships();
// this method comes from the SynchronizationPolicy
this->sync_wait_result_release();
}
Expand Down
63 changes: 63 additions & 0 deletions rclcpp/test/rclcpp/executors/test_executors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1099,3 +1099,66 @@ TYPED_TEST(TestExecutors, dropSomeNodesWithSubscription)

ASSERT_TRUE(sub1_works);
}

TYPED_TEST(TestExecutors, dropSubscriptionDuringCallback)
{
using ExecutorType = TypeParam;
ExecutorType executor;


auto node = std::make_shared<rclcpp::Node>("test_node");

bool sub1_works = false;
bool sub2_works = false;

auto cbg = node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive, true);
rclcpp::SubscriptionOptions sub_ops;
sub_ops.callback_group = cbg;

rclcpp::SubscriptionBase::SharedPtr sub1;
rclcpp::SubscriptionBase::SharedPtr sub2;

// Note, the executor uses an unordered map internally, to order
// the entities added to the rcl waitset therefore the order of the subscriptions
// is kind of undefined. Therefore each sub deletes the other one.
sub1 = node->create_subscription<test_msgs::msg::Empty>("/test_drop", 10,
[&sub1_works, &sub2](const test_msgs::msg::Empty &) {
sub1_works = true;
// delete the other subscriber
sub2.reset();
}, sub_ops);
sub2 = node->create_subscription<test_msgs::msg::Empty>("/test_drop", 10,
[&sub2_works, &sub1](const test_msgs::msg::Empty &) {
sub2_works = true;
// delete the other subscriber
sub1.reset();
}, sub_ops);

auto pub = node->create_publisher<test_msgs::msg::Empty>("/test_drop", 10);

// wait for both subs to be connected
auto max_end_time = std::chrono::steady_clock::now() + std::chrono::milliseconds(1500);
while ((sub1->get_publisher_count() == 0) || (sub2->get_publisher_count() == 0)) {
const auto cur_time = std::chrono::steady_clock::now();
ASSERT_LT(cur_time, max_end_time);
}

executor.add_node(node);

// publish some messages, until one subscriber fired. As both subscribers are
// connected to the same topic, they should fire in the same wait.
max_end_time = std::chrono::steady_clock::now() + std::chrono::milliseconds(100);
while (!sub1_works && !sub2_works) {
pub->publish(test_msgs::msg::Empty());

// let the executor pick up the node and the timers
executor.spin_all(std::chrono::milliseconds(10));

const auto cur_time = std::chrono::steady_clock::now();
ASSERT_LT(cur_time, max_end_time);
}

// only one subscriber must have worked, as the other
// one was deleted during the callback
ASSERT_TRUE(!sub1_works || !sub2_works);
}