Skip to content

Commit ec40fc6

Browse files
mergify[bot]nadavelkabetsfujitatomoya
authored
Feature: add executor.create_future() (backport #1495) (#1500)
* Feature: add executor.create_future() (#1495) * feature: add create_future and test Signed-off-by: Nadav Elkabets <[email protected]> * Use create_future in all executor tests Signed-off-by: Nadav Elkabets <[email protected]> --------- Signed-off-by: Nadav Elkabets <[email protected]> (cherry picked from commit bcdd663) # Conflicts: # rclpy/src/rclpy/events_executor/events_executor.cpp # rclpy/src/rclpy/events_executor/events_executor.hpp # rclpy/test/test_executor.py * resolve conflicts. Signed-off-by: Tomoya Fujita <[email protected]> --------- Signed-off-by: Tomoya Fujita <[email protected]> Co-authored-by: Nadav Elkabets <[email protected]> Co-authored-by: Tomoya Fujita <[email protected]>
1 parent 6354da5 commit ec40fc6

File tree

4 files changed

+33
-8
lines changed

4 files changed

+33
-8
lines changed

rclpy/rclpy/executors.py

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -219,6 +219,10 @@ def create_task(self, callback: Union[Callable, Coroutine], *args, **kwargs) ->
219219
# Task inherits from Future
220220
return task
221221

222+
def create_future(self) -> Future:
223+
"""Create a Future object attached to the Executor."""
224+
return Future(executor=self)
225+
222226
def shutdown(self, timeout_sec: Optional[float] = None) -> bool:
223227
"""
224228
Stop executing callbacks and wait for their completion.

rclpy/src/rclpy/events_executor/events_executor.cpp

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -52,6 +52,7 @@ EventsExecutor::EventsExecutor(py::object context)
5252
inspect_iscoroutine_(py::module_::import("inspect").attr("iscoroutine")),
5353
inspect_signature_(py::module_::import("inspect").attr("signature")),
5454
rclpy_task_(py::module_::import("rclpy.task").attr("Task")),
55+
rclpy_future_(py::module_::import("rclpy.task").attr("Future")),
5556
signal_callback_([this]() {events_queue_.Stop();}),
5657
rcl_callback_manager_(&events_queue_),
5758
timers_manager_(
@@ -77,6 +78,12 @@ pybind11::object EventsExecutor::create_task(
7778
return task;
7879
}
7980

81+
pybind11::object EventsExecutor::create_future()
82+
{
83+
using py::literals::operator""_a;
84+
return rclpy_future_("executor"_a = py::cast(this));
85+
}
86+
8087
bool EventsExecutor::shutdown(std::optional<double> timeout)
8188
{
8289
// NOTE: The rclpy context can invoke this with a lock on the context held. Therefore we must
@@ -881,6 +888,7 @@ void define_events_executor(py::object module)
881888
.def(py::init<py::object>(), py::arg("context"))
882889
.def_property_readonly("context", &EventsExecutor::get_context)
883890
.def("create_task", &EventsExecutor::create_task, py::arg("callback"))
891+
.def("create_future", &EventsExecutor::create_future)
884892
.def("shutdown", &EventsExecutor::shutdown, py::arg("timeout_sec") = py::none())
885893
.def("add_node", &EventsExecutor::add_node, py::arg("node"))
886894
.def("remove_node", &EventsExecutor::remove_node, py::arg("node"))

rclpy/src/rclpy/events_executor/events_executor.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -66,6 +66,7 @@ class EventsExecutor
6666
pybind11::object get_context() const {return rclpy_context_;}
6767
pybind11::object create_task(
6868
pybind11::object callback, pybind11::args args = {}, const pybind11::kwargs & kwargs = {});
69+
pybind11::object create_future();
6970
bool shutdown(std::optional<double> timeout_sec = {});
7071
bool add_node(pybind11::object node);
7172
void remove_node(pybind11::handle node);
@@ -167,6 +168,7 @@ class EventsExecutor
167168
const pybind11::object inspect_iscoroutine_;
168169
const pybind11::object inspect_signature_;
169170
const pybind11::object rclpy_task_;
171+
const pybind11::object rclpy_future_;
170172

171173
EventsQueue events_queue_;
172174
ScopedSignalCallback signal_callback_;

rclpy/test/test_executor.py

Lines changed: 19 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -452,7 +452,7 @@ def timer_callback() -> None:
452452
timer = self.node.create_timer(0.003, timer_callback)
453453

454454
# Timeout
455-
future = Future()
455+
future = executor.create_future()
456456
self.assertFalse(future.done())
457457
start = time.perf_counter()
458458
executor.spin_until_future_complete(future=future, timeout_sec=0.1)
@@ -479,7 +479,7 @@ def set_future_result(future):
479479
future.set_result('finished')
480480

481481
# Future complete timeout_sec > 0
482-
future = Future()
482+
future = executor.create_future()
483483
self.assertFalse(future.done())
484484
t = threading.Thread(target=lambda: set_future_result(future))
485485
t.start()
@@ -488,7 +488,7 @@ def set_future_result(future):
488488
self.assertEqual(future.result(), 'finished')
489489

490490
# Future complete timeout_sec = None
491-
future = Future()
491+
future = executor.create_future()
492492
self.assertFalse(future.done())
493493
t = threading.Thread(target=lambda: set_future_result(future))
494494
t.start()
@@ -497,7 +497,7 @@ def set_future_result(future):
497497
self.assertEqual(future.result(), 'finished')
498498

499499
# Future complete timeout < 0
500-
future = Future()
500+
future = executor.create_future()
501501
self.assertFalse(future.done())
502502
t = threading.Thread(target=lambda: set_future_result(future))
503503
t.start()
@@ -519,7 +519,7 @@ def timer_callback() -> None:
519519
timer = self.node.create_timer(0.003, timer_callback)
520520

521521
# Do not wait timeout_sec = 0
522-
future = Future()
522+
future = executor.create_future()
523523
self.assertFalse(future.done())
524524
executor.spin_until_future_complete(future=future, timeout_sec=0)
525525
self.assertFalse(future.done())
@@ -602,7 +602,7 @@ def test_single_threaded_spin_once_until_future(self):
602602
with self.subTest(cls=cls):
603603
executor = cls(context=self.context)
604604

605-
future = Future(executor=executor)
605+
future = executor.create_future()
606606

607607
# Setup a thread to spin_once_until_future_complete, which will spin
608608
# for a maximum of 10 seconds.
@@ -630,7 +630,7 @@ def test_multi_threaded_spin_once_until_future(self):
630630
self.assertIsNotNone(self.node.handle)
631631
executor = MultiThreadedExecutor(context=self.context)
632632

633-
future = Future(executor=executor)
633+
future: Future[bool] = executor.create_future()
634634

635635
# Setup a thread to spin_once_until_future_complete, which will spin
636636
# for a maximum of 10 seconds.
@@ -679,7 +679,7 @@ def timer2_callback() -> None:
679679
timer2 = self.node.create_timer(1.5, timer2_callback, callback_group)
680680

681681
executor.add_node(self.node)
682-
future = Future(executor=executor)
682+
future = executor.create_future()
683683
executor.spin_until_future_complete(future, 4)
684684

685685
assert count == 2
@@ -689,6 +689,17 @@ def timer2_callback() -> None:
689689
self.node.destroy_timer(timer1)
690690
self.node.destroy_client(cli)
691691

692+
def test_create_future_returns_future_with_executor_attached(self) -> None:
693+
self.assertIsNotNone(self.node.handle)
694+
for cls in [SingleThreadedExecutor, MultiThreadedExecutor, EventsExecutor]:
695+
with self.subTest(cls=cls):
696+
executor = cls(context=self.context)
697+
try:
698+
fut = executor.create_future()
699+
self.assertEqual(executor, fut._executor())
700+
finally:
701+
executor.shutdown()
702+
692703

693704
if __name__ == '__main__':
694705
unittest.main()

0 commit comments

Comments
 (0)