Skip to content

Commit 68979e9

Browse files
author
Janosch Machowinski
committed
feat(Executor): Added spin API with exception handler.
Signed-off-by: Janosch Machowinski <[email protected]>
1 parent 7fd9c1a commit 68979e9

File tree

7 files changed

+37
-2
lines changed

7 files changed

+37
-2
lines changed

rclcpp/include/rclcpp/executor.hpp

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -84,6 +84,18 @@ class Executor
8484
virtual void
8585
spin() = 0;
8686

87+
/**
88+
* \sa rclcpp::Executor:spin() for more details
89+
* \throws std::runtime_error when spin() called while already spinning
90+
* @param exception_handler will be called for every exception in the processing threads
91+
*
92+
* The exception_handler can be called from multiple threads at the same time.
93+
* The exception_handler shall rethrow the exception it if wants to terminate the program.
94+
*/
95+
RCLCPP_PUBLIC
96+
virtual void
97+
spin(std::function<void(const std::exception & e)> exception_handler);
98+
8799
/// Add a callback group to an executor.
88100
/**
89101
* An executor can have zero or more callback groups which provide work during `spin` functions.

rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -79,7 +79,7 @@ class MultiThreadedExecutor : public rclcpp::Executor
7979
*/
8080
RCLCPP_PUBLIC
8181
void
82-
spin(std::function<void(const std::exception & e)> exception_handler);
82+
spin(std::function<void(const std::exception & e)> exception_handler) override;
8383

8484
RCLCPP_PUBLIC
8585
size_t

rclcpp/include/rclcpp/executors/single_threaded_executor.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -65,6 +65,8 @@ class SingleThreadedExecutor : public rclcpp::Executor
6565
void
6666
spin() override;
6767

68+
using Executor::spin;
69+
6870
private:
6971
RCLCPP_DISABLE_COPY(SingleThreadedExecutor)
7072
};

rclcpp/include/rclcpp/executors/static_single_threaded_executor.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -79,6 +79,8 @@ class StaticSingleThreadedExecutor : public rclcpp::Executor
7979
void
8080
spin() override;
8181

82+
using Executor::spin;
83+
8284
/// Static executor implementation of spin some
8385
/**
8486
* This non-blocking function will execute entities that

rclcpp/include/rclcpp/experimental/executors/events_executor/events_executor.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -92,6 +92,8 @@ class EventsExecutor : public rclcpp::Executor
9292
void
9393
spin() override;
9494

95+
using Executor::spin;
96+
9597
/// Events executor implementation of spin some
9698
/**
9799
* This non-blocking function will execute the timers and events

rclcpp/src/rclcpp/executor.cpp

Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -401,6 +401,20 @@ Executor::remove_node(std::shared_ptr<rclcpp::Node> node_ptr, bool notify)
401401
this->remove_node(node_ptr->get_node_base_interface(), notify);
402402
}
403403

404+
void
405+
Executor::spin(std::function<void(const std::exception & e)> exception_handler)
406+
{
407+
try {
408+
spin();
409+
} catch (const std::exception & e) {
410+
RCLCPP_ERROR_STREAM(
411+
rclcpp::get_logger("rclcpp"),
412+
"Exception while spinning : " << e.what());
413+
414+
exception_handler(e);
415+
}
416+
}
417+
404418
void
405419
Executor::spin_node_once_nanoseconds(
406420
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node,

rclcpp/test/benchmark/benchmark_parameter_client.cpp

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -46,7 +46,10 @@ class RemoteNodeTest : public benchmark::Fixture
4646
remote_node_name, rclcpp::NodeOptions().context(remote_context));
4747
remote_executor->add_node(remote_node);
4848

49-
remote_thread = std::thread(&rclcpp::executors::SingleThreadedExecutor::spin, remote_executor);
49+
remote_thread =
50+
std::thread(
51+
static_cast<void (rclcpp::executors::SingleThreadedExecutor::*)()>(&rclcpp::
52+
executors::SingleThreadedExecutor::spin), remote_executor);
5053
}
5154

5255
void TearDown(benchmark::State &)

0 commit comments

Comments
 (0)