Skip to content

Commit

Permalink
use executor to spin and stop node in thread
Browse files Browse the repository at this point in the history
initialize executor

set spin_thread to true in initThread

Signed-off-by: bpwilcox <bpwilcox@eng.ucsd.edu>
  • Loading branch information
bpwilcox committed Jun 19, 2019
1 parent 234725f commit aabbd6d
Show file tree
Hide file tree
Showing 2 changed files with 10 additions and 4 deletions.
3 changes: 2 additions & 1 deletion tf2_ros/include/tf2_ros/transform_listener.h
Original file line number Diff line number Diff line change
Expand Up @@ -116,7 +116,8 @@ class TransformListener
rclcpp::Subscription<tf2_msgs::msg::TFMessage>::SharedPtr message_subscription_tf_;
rclcpp::Subscription<tf2_msgs::msg::TFMessage>::SharedPtr message_subscription_tf_static_;
tf2::BufferCore & buffer_;
std::atomic<bool> stop_thread_{false};
std::unique_ptr<rclcpp::executors::SingleThreadedExecutor> executor_;
bool spin_thread_{false};
tf2::TimePoint last_update_;
};
} // namespace tf2_ros
Expand Down
11 changes: 8 additions & 3 deletions tf2_ros/src/transform_listener.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,19 +54,24 @@ TransformListener::TransformListener(tf2::BufferCore & buffer, bool spin_thread)

TransformListener::~TransformListener()
{
stop_thread_ = true;
if (spin_thread_) {
executor_->cancel();
}
}

void TransformListener::initThread(
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface)
{
stop_thread_ = false;
executor_ = std::make_unique<rclcpp::executors::SingleThreadedExecutor>();
spin_thread_ = true;
// 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) {
while (!stop_thread_ && rclcpp::ok()) {rclcpp::spin_some(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),
Expand Down

0 comments on commit aabbd6d

Please sign in to comment.