From a36fb888848fd8548d3229790387821fab565005 Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Tue, 16 Jan 2024 21:00:30 -0700 Subject: [PATCH] Switch from bind to lambda for timer callback Signed-off-by: Ryan Friedman --- src/test_tif_loader.cpp | 14 ++++++++------ 1 file changed, 8 insertions(+), 6 deletions(-) diff --git a/src/test_tif_loader.cpp b/src/test_tif_loader.cpp index f49854a..98ab52c 100644 --- a/src/test_tif_loader.cpp +++ b/src/test_tif_loader.cpp @@ -60,15 +60,17 @@ class MapPublisher : public rclcpp::Node { map_ = std::make_shared(); map_->Load(file_path, false, color_path); - timer_ = this->create_wall_timer(5s, std::bind(&MapPublisher::timer_callback, this)); + auto timer_callback = [this]() -> void { + auto msg = grid_map::GridMapRosConverter::toMessage(map_->getGridMap()); + if (msg) { + msg->header.stamp = now(); + original_map_pub_->publish(std::move(msg)); + } + }; + timer_ = this->create_wall_timer(5s, timer_callback); } private: - void timer_callback() { - auto msg = grid_map::GridMapRosConverter::toMessage(map_->getGridMap()); - msg->header.stamp = now(); - original_map_pub_->publish(std::move(msg)); - } rclcpp::TimerBase::SharedPtr timer_; rclcpp::Publisher::SharedPtr original_map_pub_; std::shared_ptr map_;