@@ -54,6 +54,50 @@ namespace executors
5454using rclcpp::executors::MultiThreadedExecutor;
5555using rclcpp::executors::SingleThreadedExecutor;
5656
57+ // / Spin (blocking) until the conditon is complete, it times out waiting, or rclcpp is interrupted.
58+ /* *
59+ * \param[in] executor The executor which will spin the node.
60+ * \param[in] node_ptr The node to spin.
61+ * \param[in] condition The callable or future to wait on. If `SUCCESS`, the condition is safe to
62+ * access after this function
63+ * \param[in] timeout Optional timeout parameter, which gets passed to
64+ * Executor::spin_node_once.
65+ * `-1` is block forever, `0` is non-blocking.
66+ * If the time spent inside the blocking loop exceeds this timeout, return a `TIMEOUT` return code.
67+ * \return The return code, one of `SUCCESS`, `INTERRUPTED`, or `TIMEOUT`.
68+ */
69+ template <typename ConditionT, typename DurationT = std::chrono::milliseconds>
70+ rclcpp::FutureReturnCode
71+ spin_node_until_complete (
72+ rclcpp::Executor & executor,
73+ rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
74+ const ConditionT & condition,
75+ DurationT timeout = DurationT(-1 ))
76+ {
77+ // TODO(wjwwood): does not work recursively; can't call spin_node_until_complete
78+ // inside a callback executed by an executor.
79+ executor.add_node (node_ptr);
80+ auto retcode = executor.spin_until_complete (condition, timeout);
81+ executor.remove_node (node_ptr);
82+ return retcode;
83+ }
84+
85+ template <typename NodeT = rclcpp::Node, typename ConditionT,
86+ typename DurationT = std::chrono::milliseconds>
87+ rclcpp::FutureReturnCode
88+ spin_node_until_complete (
89+ rclcpp::Executor & executor,
90+ std::shared_ptr<NodeT> node_ptr,
91+ const ConditionT & condition,
92+ DurationT timeout = DurationT(-1 ))
93+ {
94+ return rclcpp::executors::spin_node_until_complete (
95+ executor,
96+ node_ptr->get_node_base_interface (),
97+ condition,
98+ timeout);
99+ }
100+
57101// / Spin (blocking) until the future is complete, it times out waiting, or rclcpp is interrupted.
58102/* *
59103 * \param[in] executor The executor which will spin the node.
@@ -67,31 +111,34 @@ using rclcpp::executors::SingleThreadedExecutor;
67111 * \return The return code, one of `SUCCESS`, `INTERRUPTED`, or `TIMEOUT`.
68112 */
69113template <typename FutureT, typename TimeRepT = int64_t , typename TimeT = std::milli>
114+ [[deprecated(
115+ " use spin_node_until_complete(Executor &, node_interfaces::NodeBaseInterface::SharedPtr, "
116+ " const ConditionT &, DurationT) instead"
117+ )]]
70118rclcpp::FutureReturnCode
71119spin_node_until_future_complete (
72120 rclcpp::Executor & executor,
73121 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
74122 const FutureT & future,
75123 std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1 ))
76124{
77- // TODO(wjwwood): does not work recursively; can't call spin_node_until_future_complete
78- // inside a callback executed by an executor.
79- executor.add_node (node_ptr);
80- auto retcode = executor.spin_until_future_complete (future, timeout);
81- executor.remove_node (node_ptr);
82- return retcode;
125+ return spin_until_complete (executor, node_ptr, future, timeout);
83126}
84127
85128template <typename NodeT = rclcpp::Node, typename FutureT, typename TimeRepT = int64_t ,
86129 typename TimeT = std::milli>
130+ [[deprecated(
131+ " use spin_node_until_complete(Executor &, std::shared_ptr<NodeT>, "
132+ " const ConditionT &, DurationT) instead"
133+ )]]
87134rclcpp::FutureReturnCode
88135spin_node_until_future_complete (
89136 rclcpp::Executor & executor,
90137 std::shared_ptr<NodeT> node_ptr,
91138 const FutureT & future,
92139 std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1 ))
93140{
94- return rclcpp::executors::spin_node_until_future_complete (
141+ return rclcpp::executors::spin_node_until_complete (
95142 executor,
96143 node_ptr->get_node_base_interface (),
97144 future,
@@ -100,26 +147,56 @@ spin_node_until_future_complete(
100147
101148} // namespace executors
102149
150+ template <typename ConditionT, typename DurationT = std::chrono::milliseconds>
151+ rclcpp::FutureReturnCode
152+ spin_until_complete (
153+ rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
154+ const ConditionT & condition,
155+ DurationT timeout = DurationT(-1 ))
156+ {
157+ rclcpp::executors::SingleThreadedExecutor executor;
158+ return executors::spin_node_until_complete<ConditionT>(executor, node_ptr, condition, timeout);
159+ }
160+
161+ template <typename NodeT = rclcpp::Node, typename ConditionT,
162+ typename DurationT = std::chrono::milliseconds>
163+ rclcpp::FutureReturnCode
164+ spin_until_complete (
165+ std::shared_ptr<NodeT> node_ptr,
166+ const ConditionT & condition,
167+ DurationT timeout = DurationT(-1 ))
168+ {
169+ return rclcpp::spin_until_complete (node_ptr->get_node_base_interface (), condition, timeout);
170+ }
171+
103172template <typename FutureT, typename TimeRepT = int64_t , typename TimeT = std::milli>
173+ [[deprecated(
174+ " use spin_until_complete(node_interfaces::NodeBaseInterface::SharedPtr, "
175+ " const ConditionT &,DurationT) instead"
176+ )]]
104177rclcpp::FutureReturnCode
105178spin_until_future_complete (
106179 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
107180 const FutureT & future,
108181 std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1 ))
109182{
110183 rclcpp::executors::SingleThreadedExecutor executor;
111- return executors::spin_node_until_future_complete <FutureT>(executor, node_ptr, future, timeout);
184+ return executors::spin_node_until_complete <FutureT>(executor, node_ptr, future, timeout);
112185}
113186
114187template <typename NodeT = rclcpp::Node, typename FutureT, typename TimeRepT = int64_t ,
115188 typename TimeT = std::milli>
189+ [[deprecated(
190+ " use spin_until_complete(std::shared_ptr<NodeT>, const ConditionT &, "
191+ " DurationT) instead"
192+ )]]
116193rclcpp::FutureReturnCode
117194spin_until_future_complete (
118195 std::shared_ptr<NodeT> node_ptr,
119196 const FutureT & future,
120197 std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1 ))
121198{
122- return rclcpp::spin_until_future_complete (node_ptr->get_node_base_interface (), future, timeout);
199+ return rclcpp::spin_until_complete (node_ptr->get_node_base_interface (), future, timeout);
123200}
124201
125202} // namespace rclcpp
0 commit comments