15 #ifndef RCLCPP__EXECUTOR_HPP_ 16 #define RCLCPP__EXECUTOR_HPP_ 72 size_t max_conditions = 0;
75 static inline ExecutorArgs create_default_executor_arguments()
122 add_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
bool notify =
true);
127 add_node(std::shared_ptr<rclcpp::node::Node> node_ptr,
bool notify =
true);
138 remove_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
bool notify =
true);
143 remove_node(std::shared_ptr<rclcpp::node::Node> node_ptr,
bool notify =
true);
152 template<
typename T = std::milli>
155 std::chrono::duration<int64_t, T> timeout = std::chrono::duration<int64_t, T>(-1))
157 return spin_node_once_nanoseconds(
159 std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
164 template<
typename NodeT = rclcpp::node::Node,
typename T = std::milli>
167 std::chrono::duration<int64_t, T> timeout = std::chrono::duration<int64_t, T>(-1))
169 return spin_node_once_nanoseconds(
170 node->get_node_base_interface(),
171 std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
181 spin_node_some(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node);
186 spin_node_some(std::shared_ptr<rclcpp::node::Node> node);
201 spin_once(std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
213 template<
typename ResponseT,
typename TimeT = std::milli>
216 std::shared_future<ResponseT> & future,
217 std::chrono::duration<int64_t, TimeT> timeout = std::chrono::duration<int64_t, TimeT>(-1))
224 std::future_status status = future.wait_for(std::chrono::seconds(0));
225 if (status == std::future_status::ready) {
226 return FutureReturnCode::SUCCESS;
229 auto end_time = std::chrono::steady_clock::now();
230 std::chrono::nanoseconds timeout_ns = std::chrono::duration_cast<std::chrono::nanoseconds>(
232 if (timeout_ns > std::chrono::nanoseconds::zero()) {
233 end_time += timeout_ns;
235 std::chrono::nanoseconds timeout_left = timeout_ns;
239 spin_once(timeout_left);
241 status = future.wait_for(std::chrono::seconds(0));
242 if (status == std::future_status::ready) {
243 return FutureReturnCode::SUCCESS;
246 if (timeout_ns < std::chrono::nanoseconds::zero()) {
250 auto now = std::chrono::steady_clock::now();
251 if (now >= end_time) {
252 return FutureReturnCode::TIMEOUT;
255 timeout_left = std::chrono::duration_cast<std::chrono::nanoseconds>(end_time - now);
259 return FutureReturnCode::INTERRUPTED;
276 set_memory_strategy(memory_strategy::MemoryStrategy::SharedPtr memory_strategy);
281 spin_node_once_nanoseconds(
282 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node,
283 std::chrono::nanoseconds timeout);
291 execute_any_executable(AnyExecutable::SharedPtr any_exec);
295 execute_subscription(
296 rclcpp::subscription::SubscriptionBase::SharedPtr subscription);
300 execute_intra_process_subscription(
301 rclcpp::subscription::SubscriptionBase::SharedPtr subscription);
305 execute_timer(rclcpp::timer::TimerBase::SharedPtr timer);
309 execute_service(rclcpp::service::ServiceBase::SharedPtr service);
313 execute_client(rclcpp::client::ClientBase::SharedPtr client);
317 wait_for_work(std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
320 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr
321 get_node_by_group(rclcpp::callback_group::CallbackGroup::SharedPtr group);
324 rclcpp::callback_group::CallbackGroup::SharedPtr
325 get_group_by_timer(rclcpp::timer::TimerBase::SharedPtr timer);
329 get_next_timer(AnyExecutable::SharedPtr any_exec);
332 AnyExecutable::SharedPtr
333 get_next_ready_executable();
336 AnyExecutable::SharedPtr
337 get_next_executable(std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
354 std::vector<rclcpp::node_interfaces::NodeBaseInterface::WeakPtr> weak_nodes_;
360 #endif // RCLCPP__EXECUTOR_HPP_
bool ok()
Check rclcpp's status.
#define RCLCPP_DISABLE_COPY(...)
Definition: macros.hpp:26
std::atomic_bool spinning
Spinning state, used to prevent multi threaded calls to spin and to cancel blocking spins...
Definition: executor.hpp:340
FutureReturnCode spin_until_future_complete(std::shared_future< ResponseT > &future, std::chrono::duration< int64_t, TimeT > timeout=std::chrono::duration< int64_t, TimeT >(-1))
Spin (blocking) until the future is complete, it times out waiting, or rclcpp is interrupted.
Definition: executor.hpp:215
void spin_node_once(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node, std::chrono::duration< int64_t, T > timeout=std::chrono::duration< int64_t, T >(-1))
Add a node to executor, execute the next available unit of work, and remove the node.
Definition: executor.hpp:154
Definition: allocator_common.hpp:24
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)
void spin_node_once(std::shared_ptr< NodeT > node, std::chrono::duration< int64_t, T > timeout=std::chrono::duration< int64_t, T >(-1))
Convenience function which takes Node and forwards NodeBaseInterface.
Definition: executor.hpp:166
memory_strategy::MemoryStrategy::SharedPtr memory_strategy_
The memory strategy: an interface for handling user-defined memory allocation strategies.
Definition: executor.hpp:349
Coordinate the order and timing of available communication tasks.
Definition: executor.hpp:93
Node is the single point of entry for creating publishers and subscribers.
Definition: node.hpp:62
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:55
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
size_t max_conditions
Definition: executor.hpp:72
memory_strategy::MemoryStrategy::SharedPtr memory_strategy
Definition: executor.hpp:71
Definition: executor.hpp:69
void spin(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr)
Create a default single-threaded executor and spin the specified node.