Skip to content

Commit

Permalink
capture local executor in lambda
Browse files Browse the repository at this point in the history
  • Loading branch information
bpwilcox committed Jul 24, 2019
1 parent 249fe87 commit 4160862
Showing 1 changed file with 9 additions and 9 deletions.
18 changes: 9 additions & 9 deletions tf2_ros/src/transform_listener.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,27 +54,27 @@ TransformListener::TransformListener(tf2::BufferCore & buffer, bool spin_thread)

TransformListener::~TransformListener()
{
if (executor_) {
executor_->cancel();
}
}

void TransformListener::initThread(
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface)
{
executor_ = std::make_unique<rclcpp::executors::SingleThreadedExecutor>();
auto executor = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();

// This lambda is required because `std::thread` cannot infer the correct
// rclcpp::spin, since there are more than one versions of it (overloaded).
// see: http://stackoverflow.com/a/27389714/671658
// I (wjwwood) chose to use the lamda rather than the static cast solution.
auto run_func = [&](rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface) {
executor_->add_node(node_base_interface);
executor_->spin();
executor_->remove_node(node_base_interface);
auto run_func =
[executor](rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface) {
executor->add_node(node_base_interface);
executor->spin();
executor->remove_node(node_base_interface);
};
dedicated_listener_thread_ = thread_ptr(
new std::thread(run_func, node_base_interface),
[](std::thread * t) {
[executor](std::thread * t) {
executor->cancel();
t->join();
delete t;
// TODO(tfoote) reenable callback queue processing
Expand Down

0 comments on commit 4160862

Please sign in to comment.