|
| 1 | +// Copyright 2015 Open Source Robotics Foundation, Inc. |
| 2 | +// |
| 3 | +// Licensed under the Apache License, Version 2.0 (the "License"); |
| 4 | +// you may not use this file except in compliance with the License. |
| 5 | +// You may obtain a copy of the License at |
| 6 | +// |
| 7 | +// http://www.apache.org/licenses/LICENSE-2.0 |
| 8 | +// |
| 9 | +// Unless required by applicable law or agreed to in writing, software |
| 10 | +// distributed under the License is distributed on an "AS IS" BASIS, |
| 11 | +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 12 | +// See the License for the specific language governing permissions and |
| 13 | +// limitations under the License. |
| 14 | + |
| 15 | +#include <chrono> |
| 16 | +#include <list> |
| 17 | +#include <memory> |
| 18 | +#include <string> |
| 19 | +#include <utility> |
| 20 | + |
| 21 | +#include "rclcpp/rclcpp.hpp" |
| 22 | +#include "rclcpp/allocator/allocator_common.hpp" |
| 23 | +#include "rclcpp/strategies/allocator_memory_strategy.hpp" |
| 24 | +#include "std_msgs/msg/u_int32.hpp" |
| 25 | + |
| 26 | +using namespace std::chrono_literals; |
| 27 | + |
| 28 | +// For demonstration purposes only, not necessary for allocator_traits |
| 29 | +static uint32_t num_allocs = 0; |
| 30 | +static uint32_t num_deallocs = 0; |
| 31 | +// A very simple custom allocator. Counts calls to allocate and deallocate. |
| 32 | +template<typename T = void> |
| 33 | +struct MyAllocator |
| 34 | +{ |
| 35 | +public: |
| 36 | + using value_type = T; |
| 37 | + using size_type = std::size_t; |
| 38 | + using pointer = T *; |
| 39 | + using const_pointer = const T *; |
| 40 | + using difference_type = typename std::pointer_traits<pointer>::difference_type; |
| 41 | + |
| 42 | + MyAllocator() noexcept |
| 43 | + { |
| 44 | + } |
| 45 | + |
| 46 | + ~MyAllocator() noexcept {} |
| 47 | + |
| 48 | + template<typename U> |
| 49 | + MyAllocator(const MyAllocator<U> &) noexcept |
| 50 | + { |
| 51 | + } |
| 52 | + |
| 53 | + T * allocate(size_t size, const void * = 0) |
| 54 | + { |
| 55 | + if (size == 0) { |
| 56 | + return nullptr; |
| 57 | + } |
| 58 | + num_allocs++; |
| 59 | + return static_cast<T *>(std::malloc(size * sizeof(T))); |
| 60 | + } |
| 61 | + |
| 62 | + void deallocate(T * ptr, size_t size) |
| 63 | + { |
| 64 | + (void)size; |
| 65 | + if (!ptr) { |
| 66 | + return; |
| 67 | + } |
| 68 | + num_deallocs++; |
| 69 | + std::free(ptr); |
| 70 | + } |
| 71 | + |
| 72 | + template<typename U> |
| 73 | + struct rebind |
| 74 | + { |
| 75 | + typedef MyAllocator<U> other; |
| 76 | + }; |
| 77 | +}; |
| 78 | + |
| 79 | +template<typename T, typename U> |
| 80 | +constexpr bool operator==( |
| 81 | + const MyAllocator<T> &, |
| 82 | + const MyAllocator<U> &) noexcept |
| 83 | +{ |
| 84 | + return true; |
| 85 | +} |
| 86 | + |
| 87 | +template<typename T, typename U> |
| 88 | +constexpr bool operator!=( |
| 89 | + const MyAllocator<T> &, |
| 90 | + const MyAllocator<U> &) noexcept |
| 91 | +{ |
| 92 | + return false; |
| 93 | +} |
| 94 | + |
| 95 | +// Override global new and delete to count calls during execution. |
| 96 | + |
| 97 | +static bool is_running = false; |
| 98 | +static uint32_t global_runtime_allocs = 0; |
| 99 | +static uint32_t global_runtime_deallocs = 0; |
| 100 | + |
| 101 | +void * operator new(std::size_t size) |
| 102 | +{ |
| 103 | + if (is_running) { |
| 104 | + global_runtime_allocs++; |
| 105 | + } |
| 106 | + return std::malloc(size); |
| 107 | +} |
| 108 | + |
| 109 | +void operator delete(void * ptr, size_t size) noexcept |
| 110 | +{ |
| 111 | + (void)size; |
| 112 | + if (ptr != nullptr) { |
| 113 | + if (is_running) { |
| 114 | + global_runtime_deallocs++; |
| 115 | + } |
| 116 | + std::free(ptr); |
| 117 | + } |
| 118 | +} |
| 119 | + |
| 120 | +void operator delete(void * ptr) noexcept |
| 121 | +{ |
| 122 | + if (ptr != nullptr) { |
| 123 | + if (is_running) { |
| 124 | + global_runtime_deallocs++; |
| 125 | + } |
| 126 | + std::free(ptr); |
| 127 | + } |
| 128 | +} |
| 129 | + |
| 130 | +int main(int argc, char ** argv) |
| 131 | +{ |
| 132 | + using rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy; |
| 133 | + using Alloc = MyAllocator<void>; |
| 134 | + using MessageAllocTraits = |
| 135 | + rclcpp::allocator::AllocRebind<std_msgs::msg::UInt32, Alloc>; |
| 136 | + using MessageAlloc = MessageAllocTraits::allocator_type; |
| 137 | + using MessageDeleter = rclcpp::allocator::Deleter<MessageAlloc, std_msgs::msg::UInt32>; |
| 138 | + using MessageUniquePtr = std::unique_ptr<std_msgs::msg::UInt32, MessageDeleter>; |
| 139 | + rclcpp::init(argc, argv); |
| 140 | + |
| 141 | + rclcpp::Node::SharedPtr node; |
| 142 | + |
| 143 | + std::list<std::string> keys = {"intra", "intraprocess", "intra-process", "intra_process"}; |
| 144 | + bool intra_process = false; |
| 145 | + |
| 146 | + printf( |
| 147 | + "This simple demo shows off a custom memory allocator to count all\n" |
| 148 | + "instances of new/delete in the program. It can be run in either regular\n" |
| 149 | + "mode (no arguments), or in intra-process mode (by passing 'intra' as a\n" |
| 150 | + "command-line argument). It will then publish a message to the\n" |
| 151 | + "'/allocator_tutorial' topic every 10 milliseconds until Ctrl-C is pressed.\n" |
| 152 | + "At that time it will print a count of the number of allocations and\n" |
| 153 | + "deallocations that happened during the program.\n\n"); |
| 154 | + |
| 155 | + if (argc > 1) { |
| 156 | + for (auto & key : keys) { |
| 157 | + if (std::string(argv[1]) == key) { |
| 158 | + intra_process = true; |
| 159 | + break; |
| 160 | + } |
| 161 | + } |
| 162 | + } |
| 163 | + |
| 164 | + if (intra_process) { |
| 165 | + printf("Intra-process pipeline is ON.\n"); |
| 166 | + auto context = rclcpp::contexts::get_global_default_context(); |
| 167 | + auto options = rclcpp::NodeOptions() |
| 168 | + .context(context) |
| 169 | + .use_intra_process_comms(true); |
| 170 | + |
| 171 | + node = rclcpp::Node::make_shared("allocator_tutorial", options); |
| 172 | + } else { |
| 173 | + auto options = rclcpp::NodeOptions() |
| 174 | + .use_intra_process_comms(false); |
| 175 | + printf("Intra-process pipeline is OFF.\n"); |
| 176 | + node = rclcpp::Node::make_shared("allocator_tutorial", options); |
| 177 | + } |
| 178 | + |
| 179 | + uint32_t counter = 0; |
| 180 | + auto callback = [&counter](std_msgs::msg::UInt32::ConstSharedPtr msg) -> void |
| 181 | + { |
| 182 | + (void)msg; |
| 183 | + ++counter; |
| 184 | + }; |
| 185 | + |
| 186 | + // Create a custom allocator and pass the allocator to the publisher and subscriber. |
| 187 | + auto alloc = std::make_shared<Alloc>(); |
| 188 | + rclcpp::PublisherOptionsWithAllocator<Alloc> publisher_options; |
| 189 | + publisher_options.allocator = alloc; |
| 190 | + auto publisher = node->create_publisher<std_msgs::msg::UInt32>( |
| 191 | + "allocator_tutorial", 10, publisher_options); |
| 192 | + |
| 193 | + rclcpp::SubscriptionOptionsWithAllocator<Alloc> subscription_options; |
| 194 | + subscription_options.allocator = alloc; |
| 195 | + auto msg_mem_strat = std::make_shared< |
| 196 | + rclcpp::message_memory_strategy::MessageMemoryStrategy< |
| 197 | + std_msgs::msg::UInt32, Alloc>>(alloc); |
| 198 | + auto subscriber = node->create_subscription<std_msgs::msg::UInt32>( |
| 199 | + "allocator_tutorial", 10, callback, subscription_options, msg_mem_strat); |
| 200 | + |
| 201 | + // Create a MemoryStrategy, which handles the allocations made by the Executor during the |
| 202 | + // execution path, and inject the MemoryStrategy into the Executor. |
| 203 | + std::shared_ptr<rclcpp::memory_strategy::MemoryStrategy> memory_strategy = |
| 204 | + std::make_shared<AllocatorMemoryStrategy<Alloc>>(alloc); |
| 205 | + |
| 206 | + rclcpp::ExecutorOptions options; |
| 207 | + options.memory_strategy = memory_strategy; |
| 208 | + rclcpp::executors::SingleThreadedExecutor executor(options); |
| 209 | + |
| 210 | + // Add our node to the executor. |
| 211 | + executor.add_node(node); |
| 212 | + |
| 213 | + MessageDeleter message_deleter; |
| 214 | + MessageAlloc message_alloc = *alloc; |
| 215 | + rclcpp::allocator::set_allocator_for_deleter(&message_deleter, &message_alloc); |
| 216 | + |
| 217 | + rclcpp::sleep_for(1ms); |
| 218 | + is_running = true; |
| 219 | + |
| 220 | + uint32_t i = 0; |
| 221 | + while (rclcpp::ok()) { |
| 222 | + // Create a message with the custom allocator, so that when the Executor deallocates the |
| 223 | + // message on the execution path, it will use the custom deallocate. |
| 224 | + auto ptr = MessageAllocTraits::allocate(message_alloc, 1); |
| 225 | + MessageAllocTraits::construct(message_alloc, ptr); |
| 226 | + MessageUniquePtr msg(ptr, message_deleter); |
| 227 | + msg->data = i; |
| 228 | + ++i; |
| 229 | + publisher->publish(std::move(msg)); |
| 230 | + rclcpp::sleep_for(10ms); |
| 231 | + executor.spin_some(); |
| 232 | + } |
| 233 | + is_running = false; |
| 234 | + |
| 235 | + uint32_t final_global_allocs = global_runtime_allocs; |
| 236 | + uint32_t final_global_deallocs = global_runtime_deallocs; |
| 237 | + printf("Global new was called %u times during spin\n", final_global_allocs); |
| 238 | + printf("Global delete was called %u times during spin\n", final_global_deallocs); |
| 239 | + |
| 240 | + printf("Allocator new was called %u times during spin\n", num_allocs); |
| 241 | + printf("Allocator delete was called %u times during spin\n", num_deallocs); |
| 242 | + |
| 243 | + return 0; |
| 244 | +} |
0 commit comments