rclcpp
master
C++ ROS Client Library API
|
Go to the documentation of this file.
15 #ifndef RCLCPP__EXECUTORS_HPP_
16 #define RCLCPP__EXECUTORS_HPP_
35 spin_some(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr);
39 spin_some(rclcpp::Node::SharedPtr node_ptr);
45 spin(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr);
49 spin(rclcpp::Node::SharedPtr node_ptr);
69 template<
typename ResponseT,
typename TimeRepT =
int64_t,
typename TimeT = std::milli>
73 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
85 template<
typename NodeT =
rclcpp::Node,
typename ResponseT,
typename TimeRepT = int64_t,
96 node_ptr->get_node_base_interface(),
103 template<
typename FutureT,
typename TimeRepT =
int64_t,
typename TimeT = std::milli>
106 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
111 return executors::spin_node_until_future_complete<FutureT>(executor, node_ptr, future, timeout);
114 template<
typename NodeT =
rclcpp::Node,
typename FutureT,
typename TimeRepT = int64_t,
127 #endif // RCLCPP__EXECUTORS_HPP_
FutureReturnCode
Return codes to be used with spin_until_future_complete.
Definition: future_return_code.hpp:33
Coordinate the order and timing of available communication tasks.
Definition: executor.hpp:58
This header provides the get_node_base_interface() template function.
Definition: allocator_common.hpp:24
void spin_some(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr)
Create a default single-threaded executor and execute any immediately available work.
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
rclcpp::FutureReturnCode spin_until_future_complete(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, const std::shared_future< FutureT > &future, std::chrono::duration< TimeRepT, TimeT > timeout=std::chrono::duration< TimeRepT, TimeT >(-1))
Definition: executors.hpp:105
Node is the single point of entry for creating publishers and subscribers.
Definition: node.hpp:74
Single-threaded executor implementation.
Definition: single_threaded_executor.hpp:42
virtual void remove_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, bool notify=true)
Remove a node from the executor.
rclcpp::FutureReturnCode spin_node_until_future_complete(rclcpp::Executor &executor, rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, const 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: executors.hpp:71
virtual void add_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, bool notify=true)
Add a node to the executor.
FutureReturnCode spin_until_future_complete(const 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:194
Definition: multi_threaded_executor.hpp:35
void spin(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr)
Create a default single-threaded executor and spin the specified node.