Skip to content

Commit 811104a

Browse files
Janosch MachowinskiJanosch Machowinski
authored andcommitted
fix: Allow usage of spin_node_until_future_complete with arbitary executers
This allows us to use executers that are not derived from rclcpp::Executor. Signed-off-by: Janosch Machowinski <[email protected]>
1 parent 0d95d03 commit 811104a

File tree

1 file changed

+6
-4
lines changed

1 file changed

+6
-4
lines changed

rclcpp/include/rclcpp/executors.hpp

Lines changed: 6 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -79,10 +79,11 @@ using rclcpp::executors::SingleThreadedExecutor;
7979
* If the time spent inside the blocking loop exceeds this timeout, return a `TIMEOUT` return code.
8080
* \return The return code, one of `SUCCESS`, `INTERRUPTED`, or `TIMEOUT`.
8181
*/
82-
template<typename FutureT, typename TimeRepT = int64_t, typename TimeT = std::milli>
82+
template<typename FutureT, typename Executor, typename TimeRepT = int64_t,
83+
typename TimeT = std::milli>
8384
rclcpp::FutureReturnCode
8485
spin_node_until_future_complete(
85-
rclcpp::Executor & executor,
86+
Executor & executor,
8687
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
8788
const FutureT & future,
8889
std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
@@ -95,11 +96,12 @@ spin_node_until_future_complete(
9596
return retcode;
9697
}
9798

98-
template<typename NodeT = rclcpp::Node, typename FutureT, typename TimeRepT = int64_t,
99+
template<typename NodeT = rclcpp::Node, typename FutureT, typename Executor,
100+
typename TimeRepT = int64_t,
99101
typename TimeT = std::milli>
100102
rclcpp::FutureReturnCode
101103
spin_node_until_future_complete(
102-
rclcpp::Executor & executor,
104+
Executor & executor,
103105
std::shared_ptr<NodeT> node_ptr,
104106
const FutureT & future,
105107
std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))

0 commit comments

Comments
 (0)