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

Corrected publish calls with shared_ptr signature #75

Closed
Closed
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
32 changes: 22 additions & 10 deletions tlsf_cpp/example/allocator_example.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#include <list>
#include <memory>
#include <string>
#include <utility>

#include "rclcpp/rclcpp.hpp"
#include "rclcpp/strategies/allocator_memory_strategy.hpp"
Expand All @@ -27,6 +28,7 @@ using TLSFAllocator = tlsf_heap_allocator<T>;
int main(int argc, char ** argv)
{
using rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy;
using Alloc = TLSFAllocator<void>;
rclcpp::init(argc, argv);

rclcpp::Node::SharedPtr node;
Expand All @@ -48,7 +50,7 @@ int main(int argc, char ** argv)
auto context = rclcpp::contexts::default_context::get_global_default_context();
auto ipm_state =
std::make_shared<
rclcpp::intra_process_manager::IntraProcessManagerImpl<TLSFAllocator<void>>>();
rclcpp::intra_process_manager::IntraProcessManagerImpl<Alloc>>();
// Constructs the intra-process manager with a custom allocator.
context->get_sub_context<rclcpp::intra_process_manager::IntraProcessManager>(ipm_state);

Expand All @@ -73,24 +75,24 @@ int main(int argc, char ** argv)
};

// Create a custom allocator and pass the allocator to the publisher and subscriber.
auto alloc = std::make_shared<TLSFAllocator<void>>();
rclcpp::PublisherOptionsWithAllocator<TLSFAllocator<void>> publisher_options;
auto alloc = std::make_shared<Alloc>();
rclcpp::PublisherOptionsWithAllocator<Alloc> publisher_options;
publisher_options.allocator = alloc;
auto publisher = node->create_publisher<std_msgs::msg::UInt32>(
"allocator_example", 10, publisher_options);

rclcpp::SubscriptionOptionsWithAllocator<TLSFAllocator<void>> subscription_options;
rclcpp::SubscriptionOptionsWithAllocator<Alloc> subscription_options;
subscription_options.allocator = alloc;
auto msg_mem_strat = std::make_shared<
rclcpp::message_memory_strategy::MessageMemoryStrategy<
std_msgs::msg::UInt32, TLSFAllocator<void>>>(alloc);
std_msgs::msg::UInt32, Alloc>>(alloc);
auto subscriber = node->create_subscription<std_msgs::msg::UInt32>(
"allocator_example", callback, 10, subscription_options, msg_mem_strat);

// Create a MemoryStrategy, which handles the allocations made by the Executor during the
// execution path, and inject the MemoryStrategy into the Executor.
std::shared_ptr<rclcpp::memory_strategy::MemoryStrategy> memory_strategy =
std::make_shared<AllocatorMemoryStrategy<TLSFAllocator<void>>>(alloc);
std::make_shared<AllocatorMemoryStrategy<Alloc>>(alloc);

rclcpp::executor::ExecutorArgs args;
args.memory_strategy = memory_strategy;
Expand All @@ -99,18 +101,28 @@ int main(int argc, char ** argv)
// Add our node to the executor.
executor.add_node(node);

// Create a message with the custom allocator, so that when the Executor deallocates the
// message on the execution path, it will use the custom deallocate.
auto msg = std::allocate_shared<std_msgs::msg::UInt32>(*alloc.get());
using MessageAllocTraits =
rclcpp::allocator::AllocRebind<std_msgs::msg::UInt32, Alloc>;
using MessageAlloc = MessageAllocTraits::allocator_type;
using MessageDeleter = rclcpp::allocator::Deleter<MessageAlloc, std_msgs::msg::UInt32>;
using MessageUniquePtr = std::unique_ptr<std_msgs::msg::UInt32, MessageDeleter>;
MessageDeleter message_deleter;
MessageAlloc message_alloc = *alloc;
rclcpp::allocator::set_allocator_for_deleter(&message_deleter, &message_alloc);

rclcpp::sleep_for(std::chrono::milliseconds(1));


uint32_t i = 0;
while (rclcpp::ok() && i < 100) {
// Create a message with the custom allocator, so that when the Executor deallocates the
// message on the execution path, it will use the custom deallocate.
auto ptr = MessageAllocTraits::allocate(message_alloc, 1);
MessageAllocTraits::construct(message_alloc, ptr);
MessageUniquePtr msg(ptr, message_deleter);
msg->data = i;
++i;
publisher->publish(msg);
publisher->publish(std::move(msg));
rclcpp::sleep_for(std::chrono::milliseconds(1));
executor.spin_some();
}
Expand Down
33 changes: 3 additions & 30 deletions tlsf_cpp/test/test_tlsf.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,8 @@
#include <memory>
#include <string>
#include <vector>
#include <utility>

#include "gtest/gtest.h"

#ifdef __GNUC__
Expand Down Expand Up @@ -346,35 +348,6 @@ TEST_F(CLASSNAME(AllocatorTest, RMW_IMPLEMENTATION), type_traits_test) {
"void unique ptr failed");
}

TEST_F(CLASSNAME(AllocatorTest, RMW_IMPLEMENTATION), allocator_shared_ptr) {
initialize(false, "allocator_shared_ptr");
size_t counter = 0;
auto callback = [&counter](std_msgs::msg::UInt32::SharedPtr msg) -> void
{
EXPECT_EQ(counter, msg->data);
counter++;
};

rclcpp::subscription_traits::has_message_type<decltype(callback)>::type a;
auto subscriber = node_->create_subscription<std_msgs::msg::UInt32>(
"allocator_shared_ptr", callback, 10, subscription_options_, msg_memory_strategy_);
// Create msg to be published
auto msg = std::allocate_shared<std_msgs::msg::UInt32>(*alloc.get());

rclcpp::sleep_for(std::chrono::milliseconds(1));
// After test_initialization, global new should only be called from within TLSFAllocator.
test_init = true;
for (uint32_t i = 0; i < iterations; i++) {
msg->data = i;
publisher_->publish(msg);
rclcpp::sleep_for(std::chrono::milliseconds(1));
executor_->spin_some();
}
test_init = false;
EXPECT_FALSE(fail);
fail = false;
}

TEST_F(CLASSNAME(AllocatorTest, RMW_IMPLEMENTATION), allocator_unique_ptr) {
initialize(true, "allocator_unique_ptr");
size_t counter = 0;
Expand Down Expand Up @@ -402,7 +375,7 @@ TEST_F(CLASSNAME(AllocatorTest, RMW_IMPLEMENTATION), allocator_unique_ptr) {
auto msg = std::unique_ptr<std_msgs::msg::UInt32, UInt32Deleter>(
std::allocator_traits<UInt32Allocator>::allocate(msg_alloc, 1));
msg->data = i;
publisher_->publish(msg);
publisher_->publish(std::move(msg));
rclcpp::sleep_for(std::chrono::milliseconds(1));
executor_->spin_some();
}
Expand Down