|
18 | 18 | #include <sys/resource.h> |
19 | 19 | #include <unistd.h> |
20 | 20 |
|
21 | | -#include <rclcpp/memory_strategies.hpp> |
22 | 21 | #include <rclcpp/rclcpp.hpp> |
23 | 22 | #include <rclcpp/strategies/message_pool_memory_strategy.hpp> |
24 | 23 |
|
@@ -89,7 +88,6 @@ void init_malloc_hook() |
89 | 88 | void(*volatile __malloc_initialize_hook)(void) = init_malloc_hook; |
90 | 89 |
|
91 | 90 | using rclcpp::strategies::message_pool_memory_strategy; |
92 | | -using rclcpp::memory_strategies::HeapPoolMemoryStrategy; |
93 | 91 |
|
94 | 92 | int main(int argc, char * argv[]) |
95 | 93 | { |
@@ -119,19 +117,6 @@ int main(int argc, char * argv[]) |
119 | 117 | // Pass the input arguments to rclcpp and initialize the signal handler. |
120 | 118 | rclcpp::init(argc, argv); |
121 | 119 |
|
122 | | - // The ObjectPoolBounds struct specifies the maximum allowable numbers for subscriptions, |
123 | | - // services, clients, executables, and a shared memory pool. |
124 | | - rclcpp::memory_strategies::heap_pool_memory_strategy::ObjectPoolBounds bounds; |
125 | | - // max_subscriptions needs to be twice the number of expected subscriptions, since a different |
126 | | - // handle is allocated for intra-process subscriptions |
127 | | - bounds.set_max_subscriptions(6).set_max_services(0).set_max_clients(0); |
128 | | - bounds.set_max_executables(1).set_memory_pool_size(0); |
129 | | - |
130 | | - // These bounds are passed to the HeapPoolMemoryStrategy, which preallocates pools for each object |
131 | | - // type. If the HeapPoolMemoryStrategy is used, the executor will re-use these static object pools |
132 | | - // instead of malloc'ing and freeing these objects during execution (after spin is called). |
133 | | - auto memory_strategy = std::make_shared<HeapPoolMemoryStrategy>(bounds); |
134 | | - |
135 | 120 | // The MessagePoolMemoryStrategy preallocates a pool of messages to be used by the subscription. |
136 | 121 | // Typically, one MessagePoolMemoryStrategy is used per subscription type, and the size of the |
137 | 122 | // message pool is determined by the number of threads (the maximum number of concurrent accesses |
@@ -219,7 +204,7 @@ int main(int argc, char * argv[]) |
219 | 204 | // Initialize the executor. |
220 | 205 | // RttExecutor is a special single-threaded executor instrumented to calculate and record |
221 | 206 | // real-time performance statistics. |
222 | | - auto executor = std::make_shared<pendulum_control::RttExecutor>(memory_strategy); |
| 207 | + auto executor = std::make_shared<pendulum_control::RttExecutor>(); |
223 | 208 |
|
224 | 209 | // Add the motor and controller nodes to the executor. |
225 | 210 | executor->add_node(motor_node); |
|
0 commit comments