Skip to content

Commit 6e5838b

Browse files
author
Jackie Kay
committed
remove HeapPoolMemoryStrategy
1 parent 61c8945 commit 6e5838b

File tree

3 files changed

+4
-18
lines changed

3 files changed

+4
-18
lines changed

pendulum_control/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -46,6 +46,7 @@ add_executable_for_each_rmw_implementations(pendulum_teleop
4646
TARGET_DEPENDENCIES
4747
"rclcpp"
4848
"pendulum_msgs"
49+
"rttest"
4950
INSTALL
5051
)
5152

pendulum_control/include/pendulum_control/rtt_executor.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -40,7 +40,7 @@ class RttExecutor : public executor::Executor
4040
* Extends default Executor constructor
4141
*/
4242
RttExecutor(memory_strategy::MemoryStrategy::SharedPtr ms =
43-
memory_strategy::create_default_strategy())
43+
memory_strategies::create_default_strategy())
4444
: executor::Executor(ms), running(false)
4545
{
4646
rttest_ready = rttest_running();

pendulum_control/src/pendulum_demo.cpp

Lines changed: 2 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,6 @@
1818
#include <sys/resource.h>
1919
#include <unistd.h>
2020

21-
#include <rclcpp/memory_strategies.hpp>
2221
#include <rclcpp/rclcpp.hpp>
2322
#include <rclcpp/strategies/message_pool_memory_strategy.hpp>
2423

@@ -88,8 +87,7 @@ void init_malloc_hook()
8887
/// Set the hook for malloc initialize so that init_malloc_hook gets called.
8988
void(*volatile __malloc_initialize_hook)(void) = init_malloc_hook;
9089

91-
using rclcpp::strategies::message_pool_memory_strategy::MessagePoolMemoryStrategy;
92-
using rclcpp::memory_strategies::HeapPoolMemoryStrategy;
90+
using namespace rclcpp::strategies::message_pool_memory_strategy;
9391

9492
int main(int argc, char * argv[])
9593
{
@@ -119,19 +117,6 @@ int main(int argc, char * argv[])
119117
// Pass the input arguments to rclcpp and initialize the signal handler.
120118
rclcpp::init(argc, argv);
121119

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-
135120
// The MessagePoolMemoryStrategy preallocates a pool of messages to be used by the subscription.
136121
// Typically, one MessagePoolMemoryStrategy is used per subscription type, and the size of the
137122
// 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[])
219204
// Initialize the executor.
220205
// RttExecutor is a special single-threaded executor instrumented to calculate and record
221206
// real-time performance statistics.
222-
auto executor = std::make_shared<pendulum_control::RttExecutor>(memory_strategy);
207+
auto executor = std::make_shared<pendulum_control::RttExecutor>();
223208

224209
// Add the motor and controller nodes to the executor.
225210
executor->add_node(motor_node);

0 commit comments

Comments
 (0)