15 #ifndef RCLCPP__EXECUTOR_HPP_ 16 #define RCLCPP__EXECUTOR_HPP_ 80 static inline ExecutorArgs create_default_executor_arguments()
124 add_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
bool notify =
true);
140 remove_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
bool notify =
true);
154 template<
typename RepT =
int64_t,
typename T = std::milli>
157 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node,
160 return spin_node_once_nanoseconds(
162 std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
167 template<
typename NodeT = rclcpp::Node,
typename RepT =
int64_t,
typename T = std::milli>
173 return spin_node_once_nanoseconds(
174 node->get_node_base_interface(),
185 spin_node_some(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node);
221 template<
typename ResponseT,
typename TimeRepT =
int64_t,
typename TimeT = std::milli>
233 if (status == std::future_status::ready) {
241 end_time += timeout_ns;
247 spin_once(timeout_left);
250 if (status == std::future_status::ready) {
259 if (now >= end_time) {
284 set_memory_strategy(memory_strategy::MemoryStrategy::SharedPtr memory_strategy);
289 spin_node_once_nanoseconds(
290 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node,
303 execute_subscription(
304 rclcpp::SubscriptionBase::SharedPtr subscription);
308 execute_intra_process_subscription(
309 rclcpp::SubscriptionBase::SharedPtr subscription);
313 execute_timer(rclcpp::TimerBase::SharedPtr timer);
317 execute_service(rclcpp::ServiceBase::SharedPtr service);
321 execute_client(rclcpp::ClientBase::SharedPtr client);
328 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr
329 get_node_by_group(rclcpp::callback_group::CallbackGroup::SharedPtr group);
332 rclcpp::callback_group::CallbackGroup::SharedPtr
333 get_group_by_timer(rclcpp::TimerBase::SharedPtr timer);
374 #endif // RCLCPP__EXECUTOR_HPP_
void spin_node_once(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node, std::chrono::duration< RepT, T > timeout=std::chrono::duration< RepT, T >(-1))
Add a node to executor, execute the next available unit of work, and remove the node.
Definition: executor.hpp:156
DefaultContext::SharedPtr get_global_default_context()
#define RCLCPP_DISABLE_COPY(...)
Definition: macros.hpp:26
void spin_node_once(std::shared_ptr< NodeT > node, std::chrono::duration< RepT, T > timeout=std::chrono::duration< RepT, T >(-1))
Convenience function which takes Node and forwards NodeBaseInterface.
Definition: executor.hpp:169
std::atomic_bool spinning
Spinning state, used to prevent multi threaded calls to spin and to cancel blocking spins...
Definition: executor.hpp:350
FutureReturnCode spin_until_future_complete(std::shared_future< ResponseT > &future, std::chrono::duration< TimeRepT, TimeT > timeout=std::chrono::duration< TimeRepT, TimeT >(-1))
Spin (blocking) until the future is complete, it times out waiting, or rclcpp is interrupted.
Definition: executor.hpp:223
Definition: any_executable.hpp:35
This header provides the get_node_topics_interface() template function.
Definition: allocator_common.hpp:24
T duration_cast(T... args)
std::ostream & operator<<(std::ostream &os, const FutureReturnCode &future_return_code)
rcl_wait_set_t rcl_get_zero_initialized_wait_set(void)
memory_strategy::MemoryStrategy::SharedPtr create_default_strategy()
rcl_guard_condition_t rcl_get_zero_initialized_guard_condition(void)
std::string to_string(const FutureReturnCode &future_return_code)
std::shared_ptr< rclcpp::Context > context
Definition: executor.hpp:76
memory_strategy::MemoryStrategy::SharedPtr memory_strategy_
The memory strategy: an interface for handling user-defined memory allocation strategies.
Definition: executor.hpp:359
Coordinate the order and timing of available communication tasks.
Definition: executor.hpp:95
ExecutorArgs()
Definition: executor.hpp:69
void spin_some(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr)
Create a default single-threaded executor and execute any immediately available work.
#define RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(...)
Definition: macros.hpp:51
FutureReturnCode
Return codes to be used with spin_until_future_complete.
Definition: executor.hpp:53
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
bool ok(rclcpp::Context::SharedPtr context=nullptr)
Check rclcpp's status.
size_t max_conditions
Definition: executor.hpp:77
memory_strategy::MemoryStrategy::SharedPtr memory_strategy
Definition: executor.hpp:75
Definition: executor.hpp:67
void spin(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr)
Create a default single-threaded executor and spin the specified node.
std::shared_ptr< rclcpp::Context > context_
The context associated with this executor.
Definition: executor.hpp:362