Skip to content

Commit 8a36b9f

Browse files
nadavelkabetsmergify[bot]
authored andcommitted
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
1 parent 6354da5 commit 8a36b9f

File tree

4 files changed

+59
-2
lines changed

4 files changed

+59
-2
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: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -52,6 +52,11 @@ 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+
<<<<<<< HEAD
56+
=======
57+
rclpy_future_(py::module_::import("rclpy.task").attr("Future")),
58+
rclpy_timer_timer_info_(py::module_::import("rclpy.timer").attr("TimerInfo")),
59+
>>>>>>> bcdd663 (Feature: add executor.create_future() (#1495))
5560
signal_callback_([this]() {events_queue_.Stop();}),
5661
rcl_callback_manager_(&events_queue_),
5762
timers_manager_(
@@ -77,6 +82,12 @@ pybind11::object EventsExecutor::create_task(
7782
return task;
7883
}
7984

85+
pybind11::object EventsExecutor::create_future()
86+
{
87+
using py::literals::operator""_a;
88+
return rclpy_future_("executor"_a = py::cast(this));
89+
}
90+
8091
bool EventsExecutor::shutdown(std::optional<double> timeout)
8192
{
8293
// NOTE: The rclpy context can invoke this with a lock on the context held. Therefore we must
@@ -881,6 +892,7 @@ void define_events_executor(py::object module)
881892
.def(py::init<py::object>(), py::arg("context"))
882893
.def_property_readonly("context", &EventsExecutor::get_context)
883894
.def("create_task", &EventsExecutor::create_task, py::arg("callback"))
895+
.def("create_future", &EventsExecutor::create_future)
884896
.def("shutdown", &EventsExecutor::shutdown, py::arg("timeout_sec") = py::none())
885897
.def("add_node", &EventsExecutor::add_node, py::arg("node"))
886898
.def("remove_node", &EventsExecutor::remove_node, py::arg("node"))

rclpy/src/rclpy/events_executor/events_executor.hpp

Lines changed: 6 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,11 @@ class EventsExecutor
167168
const pybind11::object inspect_iscoroutine_;
168169
const pybind11::object inspect_signature_;
169170
const pybind11::object rclpy_task_;
171+
<<<<<<< HEAD
172+
=======
173+
const pybind11::object rclpy_future_;
174+
const pybind11::object rclpy_timer_timer_info_;
175+
>>>>>>> bcdd663 (Feature: add executor.create_future() (#1495))
170176

171177
EventsQueue events_queue_;
172178
ScopedSignalCallback signal_callback_;

rclpy/test/test_executor.py

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

454454
# Timeout
455+
<<<<<<< HEAD
455456
future = Future()
457+
=======
458+
future = executor.create_future()
459+
>>>>>>> bcdd663 (Feature: add executor.create_future() (#1495))
456460
self.assertFalse(future.done())
457461
start = time.perf_counter()
458462
executor.spin_until_future_complete(future=future, timeout_sec=0.1)
@@ -479,7 +483,11 @@ def set_future_result(future):
479483
future.set_result('finished')
480484

481485
# Future complete timeout_sec > 0
486+
<<<<<<< HEAD
482487
future = Future()
488+
=======
489+
future = executor.create_future()
490+
>>>>>>> bcdd663 (Feature: add executor.create_future() (#1495))
483491
self.assertFalse(future.done())
484492
t = threading.Thread(target=lambda: set_future_result(future))
485493
t.start()
@@ -488,7 +496,7 @@ def set_future_result(future):
488496
self.assertEqual(future.result(), 'finished')
489497

490498
# Future complete timeout_sec = None
491-
future = Future()
499+
future = executor.create_future()
492500
self.assertFalse(future.done())
493501
t = threading.Thread(target=lambda: set_future_result(future))
494502
t.start()
@@ -497,7 +505,7 @@ def set_future_result(future):
497505
self.assertEqual(future.result(), 'finished')
498506

499507
# Future complete timeout < 0
500-
future = Future()
508+
future = executor.create_future()
501509
self.assertFalse(future.done())
502510
t = threading.Thread(target=lambda: set_future_result(future))
503511
t.start()
@@ -519,7 +527,11 @@ def timer_callback() -> None:
519527
timer = self.node.create_timer(0.003, timer_callback)
520528

521529
# Do not wait timeout_sec = 0
530+
<<<<<<< HEAD
522531
future = Future()
532+
=======
533+
future = executor.create_future()
534+
>>>>>>> bcdd663 (Feature: add executor.create_future() (#1495))
523535
self.assertFalse(future.done())
524536
executor.spin_until_future_complete(future=future, timeout_sec=0)
525537
self.assertFalse(future.done())
@@ -602,7 +614,11 @@ def test_single_threaded_spin_once_until_future(self):
602614
with self.subTest(cls=cls):
603615
executor = cls(context=self.context)
604616

617+
<<<<<<< HEAD
605618
future = Future(executor=executor)
619+
=======
620+
future = executor.create_future()
621+
>>>>>>> bcdd663 (Feature: add executor.create_future() (#1495))
606622

607623
# Setup a thread to spin_once_until_future_complete, which will spin
608624
# for a maximum of 10 seconds.
@@ -630,7 +646,11 @@ def test_multi_threaded_spin_once_until_future(self):
630646
self.assertIsNotNone(self.node.handle)
631647
executor = MultiThreadedExecutor(context=self.context)
632648

649+
<<<<<<< HEAD
633650
future = Future(executor=executor)
651+
=======
652+
future: Future[bool] = executor.create_future()
653+
>>>>>>> bcdd663 (Feature: add executor.create_future() (#1495))
634654

635655
# Setup a thread to spin_once_until_future_complete, which will spin
636656
# for a maximum of 10 seconds.
@@ -679,7 +699,11 @@ def timer2_callback() -> None:
679699
timer2 = self.node.create_timer(1.5, timer2_callback, callback_group)
680700

681701
executor.add_node(self.node)
702+
<<<<<<< HEAD
682703
future = Future(executor=executor)
704+
=======
705+
future = executor.create_future()
706+
>>>>>>> bcdd663 (Feature: add executor.create_future() (#1495))
683707
executor.spin_until_future_complete(future, 4)
684708

685709
assert count == 2
@@ -689,6 +713,17 @@ def timer2_callback() -> None:
689713
self.node.destroy_timer(timer1)
690714
self.node.destroy_client(cli)
691715

716+
def test_create_future_returns_future_with_executor_attached(self) -> None:
717+
self.assertIsNotNone(self.node.handle)
718+
for cls in [SingleThreadedExecutor, MultiThreadedExecutor, EventsExecutor]:
719+
with self.subTest(cls=cls):
720+
executor = cls(context=self.context)
721+
try:
722+
fut = executor.create_future()
723+
self.assertEqual(executor, fut._executor())
724+
finally:
725+
executor.shutdown()
726+
692727

693728
if __name__ == '__main__':
694729
unittest.main()

0 commit comments

Comments
 (0)