Skip to content

Commit 88d5ea2

Browse files
authored
Switch from bind to lambda for timer callback (#43)
Signed-off-by: Ryan Friedman <[email protected]>
1 parent d33b962 commit 88d5ea2

File tree

1 file changed

+8
-6
lines changed

1 file changed

+8
-6
lines changed

src/test_tif_loader.cpp

Lines changed: 8 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -60,15 +60,17 @@ class MapPublisher : public rclcpp::Node {
6060

6161
map_ = std::make_shared<GridMapGeo>();
6262
map_->Load(file_path, false, color_path);
63-
timer_ = this->create_wall_timer(5s, std::bind(&MapPublisher::timer_callback, this));
63+
auto timer_callback = [this]() -> void {
64+
auto msg = grid_map::GridMapRosConverter::toMessage(map_->getGridMap());
65+
if (msg) {
66+
msg->header.stamp = now();
67+
original_map_pub_->publish(std::move(msg));
68+
}
69+
};
70+
timer_ = this->create_wall_timer(5s, timer_callback);
6471
}
6572

6673
private:
67-
void timer_callback() {
68-
auto msg = grid_map::GridMapRosConverter::toMessage(map_->getGridMap());
69-
msg->header.stamp = now();
70-
original_map_pub_->publish(std::move(msg));
71-
}
7274
rclcpp::TimerBase::SharedPtr timer_;
7375
rclcpp::Publisher<grid_map_msgs::msg::GridMap>::SharedPtr original_map_pub_;
7476
std::shared_ptr<GridMapGeo> map_;

0 commit comments

Comments
 (0)