@@ -54,50 +54,6 @@ 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-
10157// / Spin (blocking) until the future is complete, it times out waiting, or rclcpp is interrupted.
10258/* *
10359 * \param[in] executor The executor which will spin the node.
@@ -111,34 +67,31 @@ spin_node_until_complete(
11167 * \return The return code, one of `SUCCESS`, `INTERRUPTED`, or `TIMEOUT`.
11268 */
11369template <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- )]]
11870rclcpp::FutureReturnCode
11971spin_node_until_future_complete (
12072 rclcpp::Executor & executor,
12173 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
12274 const FutureT & future,
12375 std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1 ))
12476{
125- return spin_until_complete (executor, node_ptr, future, timeout);
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;
12683}
12784
12885template <typename NodeT = rclcpp::Node, typename FutureT, typename TimeRepT = int64_t ,
12986 typename TimeT = std::milli>
130- [[deprecated(
131- " use spin_node_until_complete(Executor &, std::shared_ptr<NodeT>, "
132- " const ConditionT &, DurationT) instead"
133- )]]
13487rclcpp::FutureReturnCode
13588spin_node_until_future_complete (
13689 rclcpp::Executor & executor,
13790 std::shared_ptr<NodeT> node_ptr,
13891 const FutureT & future,
13992 std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1 ))
14093{
141- return rclcpp::executors::spin_node_until_complete (
94+ return rclcpp::executors::spin_node_until_future_complete (
14295 executor,
14396 node_ptr->get_node_base_interface (),
14497 future,
@@ -147,56 +100,26 @@ spin_node_until_future_complete(
147100
148101} // namespace executors
149102
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-
172103template <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- )]]
177104rclcpp::FutureReturnCode
178105spin_until_future_complete (
179106 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
180107 const FutureT & future,
181108 std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1 ))
182109{
183110 rclcpp::executors::SingleThreadedExecutor executor;
184- return executors::spin_node_until_complete <FutureT>(executor, node_ptr, future, timeout);
111+ return executors::spin_node_until_future_complete <FutureT>(executor, node_ptr, future, timeout);
185112}
186113
187114template <typename NodeT = rclcpp::Node, typename FutureT, typename TimeRepT = int64_t ,
188115 typename TimeT = std::milli>
189- [[deprecated(
190- " use spin_until_complete(std::shared_ptr<NodeT>, const ConditionT &, "
191- " DurationT) instead"
192- )]]
193116rclcpp::FutureReturnCode
194117spin_until_future_complete (
195118 std::shared_ptr<NodeT> node_ptr,
196119 const FutureT & future,
197120 std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1 ))
198121{
199- return rclcpp::spin_until_complete (node_ptr->get_node_base_interface (), future, timeout);
122+ return rclcpp::spin_until_future_complete (node_ptr->get_node_base_interface (), future, timeout);
200123}
201124
202125} // namespace rclcpp
0 commit comments