rclcpp  beta1
C++ ROS Client Library API
Public Types | Public Member Functions | List of all members
rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy< Alloc > Class Template Reference

Delegate for handling memory allocations while the Executor is executing. More...

#include <allocator_memory_strategy.hpp>

Inheritance diagram for rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy< Alloc >:
rclcpp::memory_strategy::MemoryStrategy

Public Types

using ExecAllocTraits = allocator::AllocRebind< executor::AnyExecutable, Alloc >
 
using ExecAlloc = typename ExecAllocTraits::allocator_type
 
using ExecDeleter = allocator::Deleter< ExecAlloc, executor::AnyExecutable >
 
using VoidAllocTraits = typename allocator::AllocRebind< void *, Alloc >
 
using VoidAlloc = typename VoidAllocTraits::allocator_type
 
- Public Types inherited from rclcpp::memory_strategy::MemoryStrategy
using WeakNodeVector = std::vector< rclcpp::node_interfaces::NodeBaseInterface::WeakPtr >
 

Public Member Functions

 AllocatorMemoryStrategy (std::shared_ptr< Alloc > allocator)
 
 AllocatorMemoryStrategy ()
 
void add_guard_condition (const rcl_guard_condition_t *guard_condition)
 
void remove_guard_condition (const rcl_guard_condition_t *guard_condition)
 
void clear_handles ()
 
virtual void remove_null_handles (rcl_wait_set_t *wait_set)
 
bool collect_entities (const WeakNodeVector &weak_nodes)
 
bool add_handles_to_waitset (rcl_wait_set_t *wait_set)
 
executor::AnyExecutable::SharedPtr instantiate_next_executable ()
 Provide a newly initialized AnyExecutable object. More...
 
virtual void get_next_subscription (executor::AnyExecutable::SharedPtr any_exec, const WeakNodeVector &weak_nodes)
 
virtual void get_next_service (executor::AnyExecutable::SharedPtr any_exec, const WeakNodeVector &weak_nodes)
 
virtual void get_next_client (executor::AnyExecutable::SharedPtr any_exec, const WeakNodeVector &weak_nodes)
 
virtual rcl_allocator_t get_allocator ()
 
size_t number_of_ready_subscriptions () const
 
size_t number_of_ready_services () const
 
size_t number_of_ready_clients () const
 
size_t number_of_guard_conditions () const
 
size_t number_of_ready_timers () const
 
- Public Member Functions inherited from rclcpp::memory_strategy::MemoryStrategy
virtual void get_next_subscription (rclcpp::executor::AnyExecutable::SharedPtr any_exec, const WeakNodeVector &weak_nodes)=0
 
virtual void get_next_service (rclcpp::executor::AnyExecutable::SharedPtr any_exec, const WeakNodeVector &weak_nodes)=0
 
virtual void get_next_client (rclcpp::executor::AnyExecutable::SharedPtr any_exec, const WeakNodeVector &weak_nodes)=0
 

Additional Inherited Members

- Static Public Member Functions inherited from rclcpp::memory_strategy::MemoryStrategy
static rclcpp::subscription::SubscriptionBase::SharedPtr get_subscription_by_handle (const rcl_subscription_t *subscriber_handle, const WeakNodeVector &weak_nodes)
 
static rclcpp::service::ServiceBase::SharedPtr get_service_by_handle (const rcl_service_t *service_handle, const WeakNodeVector &weak_nodes)
 
static rclcpp::client::ClientBase::SharedPtr get_client_by_handle (const rcl_client_t *client_handle, const WeakNodeVector &weak_nodes)
 
static rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_by_group (rclcpp::callback_group::CallbackGroup::SharedPtr group, const WeakNodeVector &weak_nodes)
 
static rclcpp::callback_group::CallbackGroup::SharedPtr get_group_by_subscription (rclcpp::subscription::SubscriptionBase::SharedPtr subscription, const WeakNodeVector &weak_nodes)
 
static rclcpp::callback_group::CallbackGroup::SharedPtr get_group_by_service (rclcpp::service::ServiceBase::SharedPtr service, const WeakNodeVector &weak_nodes)
 
static rclcpp::callback_group::CallbackGroup::SharedPtr get_group_by_client (rclcpp::client::ClientBase::SharedPtr client, const WeakNodeVector &weak_nodes)
 

Detailed Description

template<typename Alloc = std::allocator<void>>
class rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy< Alloc >

Delegate for handling memory allocations while the Executor is executing.

By default, the memory strategy dynamically allocates memory for structures that come in from the rmw implementation after the executor waits for work, based on the number of entities that come through.

Member Typedef Documentation

§ ExecAllocTraits

§ ExecAlloc

template<typename Alloc = std::allocator<void>>
using rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy< Alloc >::ExecAlloc = typename ExecAllocTraits::allocator_type

§ ExecDeleter

§ VoidAllocTraits

template<typename Alloc = std::allocator<void>>
using rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy< Alloc >::VoidAllocTraits = typename allocator::AllocRebind<void *, Alloc>

§ VoidAlloc

template<typename Alloc = std::allocator<void>>
using rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy< Alloc >::VoidAlloc = typename VoidAllocTraits::allocator_type

Constructor & Destructor Documentation

§ AllocatorMemoryStrategy() [1/2]

template<typename Alloc = std::allocator<void>>
rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy< Alloc >::AllocatorMemoryStrategy ( std::shared_ptr< Alloc >  allocator)
inlineexplicit

§ AllocatorMemoryStrategy() [2/2]

template<typename Alloc = std::allocator<void>>
rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy< Alloc >::AllocatorMemoryStrategy ( )
inline

Member Function Documentation

§ add_guard_condition()

template<typename Alloc = std::allocator<void>>
void rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy< Alloc >::add_guard_condition ( const rcl_guard_condition_t guard_condition)
inlinevirtual

§ remove_guard_condition()

template<typename Alloc = std::allocator<void>>
void rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy< Alloc >::remove_guard_condition ( const rcl_guard_condition_t guard_condition)
inlinevirtual

§ clear_handles()

template<typename Alloc = std::allocator<void>>
void rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy< Alloc >::clear_handles ( )
inlinevirtual

§ remove_null_handles()

template<typename Alloc = std::allocator<void>>
virtual void rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy< Alloc >::remove_null_handles ( rcl_wait_set_t wait_set)
inlinevirtual

§ collect_entities()

template<typename Alloc = std::allocator<void>>
bool rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy< Alloc >::collect_entities ( const WeakNodeVector weak_nodes)
inlinevirtual

§ add_handles_to_waitset()

template<typename Alloc = std::allocator<void>>
bool rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy< Alloc >::add_handles_to_waitset ( rcl_wait_set_t wait_set)
inlinevirtual

§ instantiate_next_executable()

template<typename Alloc = std::allocator<void>>
executor::AnyExecutable::SharedPtr rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy< Alloc >::instantiate_next_executable ( )
inlinevirtual

Provide a newly initialized AnyExecutable object.

Implements rclcpp::memory_strategy::MemoryStrategy.

§ get_next_subscription()

template<typename Alloc = std::allocator<void>>
virtual void rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy< Alloc >::get_next_subscription ( executor::AnyExecutable::SharedPtr  any_exec,
const WeakNodeVector weak_nodes 
)
inlinevirtual

§ get_next_service()

template<typename Alloc = std::allocator<void>>
virtual void rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy< Alloc >::get_next_service ( executor::AnyExecutable::SharedPtr  any_exec,
const WeakNodeVector weak_nodes 
)
inlinevirtual

§ get_next_client()

template<typename Alloc = std::allocator<void>>
virtual void rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy< Alloc >::get_next_client ( executor::AnyExecutable::SharedPtr  any_exec,
const WeakNodeVector weak_nodes 
)
inlinevirtual

§ get_allocator()

template<typename Alloc = std::allocator<void>>
virtual rcl_allocator_t rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy< Alloc >::get_allocator ( )
inlinevirtual

§ number_of_ready_subscriptions()

template<typename Alloc = std::allocator<void>>
size_t rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy< Alloc >::number_of_ready_subscriptions ( ) const
inlinevirtual

§ number_of_ready_services()

template<typename Alloc = std::allocator<void>>
size_t rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy< Alloc >::number_of_ready_services ( ) const
inlinevirtual

§ number_of_ready_clients()

template<typename Alloc = std::allocator<void>>
size_t rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy< Alloc >::number_of_ready_clients ( ) const
inlinevirtual

§ number_of_guard_conditions()

template<typename Alloc = std::allocator<void>>
size_t rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy< Alloc >::number_of_guard_conditions ( ) const
inlinevirtual

§ number_of_ready_timers()

template<typename Alloc = std::allocator<void>>
size_t rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy< Alloc >::number_of_ready_timers ( ) const
inlinevirtual

The documentation for this class was generated from the following file: