@@ -67,6 +67,50 @@ namespace executors
6767using rclcpp::executors::MultiThreadedExecutor;
6868using rclcpp::executors::SingleThreadedExecutor;
6969
70+ // / Spin (blocking) until the conditon is complete, it times out waiting, or rclcpp is interrupted.
71+ /* *
72+ * \param[in] executor The executor which will spin the node.
73+ * \param[in] node_ptr The node to spin.
74+ * \param[in] condition The callable or future to wait on. If `SUCCESS`, the condition is safe to
75+ * access after this function
76+ * \param[in] timeout Optional timeout parameter, which gets passed to
77+ * Executor::spin_node_once.
78+ * `-1` is block forever, `0` is non-blocking.
79+ * If the time spent inside the blocking loop exceeds this timeout, return a `TIMEOUT` return code.
80+ * \return The return code, one of `SUCCESS`, `INTERRUPTED`, or `TIMEOUT`.
81+ */
82+ template <typename ConditionT, typename DurationT = std::chrono::milliseconds>
83+ rclcpp::FutureReturnCode
84+ spin_node_until_complete (
85+ rclcpp::Executor & executor,
86+ rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
87+ const ConditionT & condition,
88+ DurationT timeout = DurationT(-1 ))
89+ {
90+ // TODO(wjwwood): does not work recursively; can't call spin_node_until_complete
91+ // inside a callback executed by an executor.
92+ executor.add_node (node_ptr);
93+ auto retcode = executor.spin_until_complete (condition, timeout);
94+ executor.remove_node (node_ptr);
95+ return retcode;
96+ }
97+
98+ template <typename NodeT = rclcpp::Node, typename ConditionT,
99+ typename DurationT = std::chrono::milliseconds>
100+ rclcpp::FutureReturnCode
101+ spin_node_until_complete (
102+ rclcpp::Executor & executor,
103+ std::shared_ptr<NodeT> node_ptr,
104+ const ConditionT & condition,
105+ DurationT timeout = DurationT(-1 ))
106+ {
107+ return rclcpp::executors::spin_node_until_complete (
108+ executor,
109+ node_ptr->get_node_base_interface (),
110+ condition,
111+ timeout);
112+ }
113+
70114// / Spin (blocking) until the future is complete, it times out waiting, or rclcpp is interrupted.
71115/* *
72116 * \param[in] executor The executor which will spin the node.
@@ -80,31 +124,34 @@ using rclcpp::executors::SingleThreadedExecutor;
80124 * \return The return code, one of `SUCCESS`, `INTERRUPTED`, or `TIMEOUT`.
81125 */
82126template <typename FutureT, typename TimeRepT = int64_t , typename TimeT = std::milli>
127+ [[deprecated(
128+ " use spin_node_until_complete(Executor &, node_interfaces::NodeBaseInterface::SharedPtr, "
129+ " const ConditionT &, DurationT) instead"
130+ )]]
83131rclcpp::FutureReturnCode
84132spin_node_until_future_complete (
85133 rclcpp::Executor & executor,
86134 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
87135 const FutureT & future,
88136 std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1 ))
89137{
90- // TODO(wjwwood): does not work recursively; can't call spin_node_until_future_complete
91- // inside a callback executed by an executor.
92- executor.add_node (node_ptr);
93- auto retcode = executor.spin_until_future_complete (future, timeout);
94- executor.remove_node (node_ptr);
95- return retcode;
138+ return spin_until_complete (executor, node_ptr, future, timeout);
96139}
97140
98141template <typename NodeT = rclcpp::Node, typename FutureT, typename TimeRepT = int64_t ,
99142 typename TimeT = std::milli>
143+ [[deprecated(
144+ " use spin_node_until_complete(Executor &, std::shared_ptr<NodeT>, "
145+ " const ConditionT &, DurationT) instead"
146+ )]]
100147rclcpp::FutureReturnCode
101148spin_node_until_future_complete (
102149 rclcpp::Executor & executor,
103150 std::shared_ptr<NodeT> node_ptr,
104151 const FutureT & future,
105152 std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1 ))
106153{
107- return rclcpp::executors::spin_node_until_future_complete (
154+ return rclcpp::executors::spin_node_until_complete (
108155 executor,
109156 node_ptr->get_node_base_interface (),
110157 future,
@@ -113,26 +160,56 @@ spin_node_until_future_complete(
113160
114161} // namespace executors
115162
163+ template <typename ConditionT, typename DurationT = std::chrono::milliseconds>
164+ rclcpp::FutureReturnCode
165+ spin_until_complete (
166+ rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
167+ const ConditionT & condition,
168+ DurationT timeout = DurationT(-1 ))
169+ {
170+ rclcpp::executors::SingleThreadedExecutor executor;
171+ return executors::spin_node_until_complete<ConditionT>(executor, node_ptr, condition, timeout);
172+ }
173+
174+ template <typename NodeT = rclcpp::Node, typename ConditionT,
175+ typename DurationT = std::chrono::milliseconds>
176+ rclcpp::FutureReturnCode
177+ spin_until_complete (
178+ std::shared_ptr<NodeT> node_ptr,
179+ const ConditionT & condition,
180+ DurationT timeout = DurationT(-1 ))
181+ {
182+ return rclcpp::spin_until_complete (node_ptr->get_node_base_interface (), condition, timeout);
183+ }
184+
116185template <typename FutureT, typename TimeRepT = int64_t , typename TimeT = std::milli>
186+ [[deprecated(
187+ " use spin_until_complete(node_interfaces::NodeBaseInterface::SharedPtr, "
188+ " const ConditionT &,DurationT) instead"
189+ )]]
117190rclcpp::FutureReturnCode
118191spin_until_future_complete (
119192 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
120193 const FutureT & future,
121194 std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1 ))
122195{
123196 rclcpp::executors::SingleThreadedExecutor executor;
124- return executors::spin_node_until_future_complete <FutureT>(executor, node_ptr, future, timeout);
197+ return executors::spin_node_until_complete <FutureT>(executor, node_ptr, future, timeout);
125198}
126199
127200template <typename NodeT = rclcpp::Node, typename FutureT, typename TimeRepT = int64_t ,
128201 typename TimeT = std::milli>
202+ [[deprecated(
203+ " use spin_until_complete(std::shared_ptr<NodeT>, const ConditionT &, "
204+ " DurationT) instead"
205+ )]]
129206rclcpp::FutureReturnCode
130207spin_until_future_complete (
131208 std::shared_ptr<NodeT> node_ptr,
132209 const FutureT & future,
133210 std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1 ))
134211{
135- return rclcpp::spin_until_future_complete (node_ptr->get_node_base_interface (), future, timeout);
212+ return rclcpp::spin_until_complete (node_ptr->get_node_base_interface (), future, timeout);
136213}
137214
138215} // namespace rclcpp
0 commit comments