From 86342b2ff9b86cbe0232c27284c4ac20b5d98647 Mon Sep 17 00:00:00 2001 From: JaeyoungLim Date: Fri, 1 Dec 2023 09:37:52 +0100 Subject: [PATCH] Fix format --- src/test_tif_loader.cpp | 40 ++++++++++++++++++++-------------------- 1 file changed, 20 insertions(+), 20 deletions(-) diff --git a/src/test_tif_loader.cpp b/src/test_tif_loader.cpp index 9132f77..c920891 100644 --- a/src/test_tif_loader.cpp +++ b/src/test_tif_loader.cpp @@ -48,32 +48,32 @@ using namespace std::chrono_literals; class MapPublisher : public rclcpp::Node { - public: - MapPublisher() : Node("map_publisher") { - original_map_pub_ = this->create_publisher("elevation_map", 1); + public: + MapPublisher() : Node("map_publisher") { + original_map_pub_ = this->create_publisher("elevation_map", 1); - std::string file_path = this->declare_parameter("tif_path", "."); - std::string color_path = this->declare_parameter("tif_color_path", "."); + std::string file_path = this->declare_parameter("tif_path", "."); + std::string color_path = this->declare_parameter("tif_color_path", "."); - RCLCPP_INFO_STREAM(get_logger(), "file_path " << file_path); - RCLCPP_INFO_STREAM(get_logger(), "color_path " << color_path); + RCLCPP_INFO_STREAM(get_logger(), "file_path " << file_path); + RCLCPP_INFO_STREAM(get_logger(), "color_path " << color_path); - map_ = std::make_shared(); - map_->Load(file_path, false, color_path); - timer_ = this->create_wall_timer(5s, std::bind(&MapPublisher::timer_callback, this)); - } - private: - void timer_callback() { - auto msg = grid_map::GridMapRosConverter::toMessage(map_->getGridMap()); - original_map_pub_->publish(std::move(msg)); - } - rclcpp::TimerBase::SharedPtr timer_; - rclcpp::Publisher::SharedPtr original_map_pub_; - std::shared_ptr map_; + map_ = std::make_shared(); + map_->Load(file_path, false, color_path); + timer_ = this->create_wall_timer(5s, std::bind(&MapPublisher::timer_callback, this)); + } + + private: + void timer_callback() { + auto msg = grid_map::GridMapRosConverter::toMessage(map_->getGridMap()); + original_map_pub_->publish(std::move(msg)); + } + rclcpp::TimerBase::SharedPtr timer_; + rclcpp::Publisher::SharedPtr original_map_pub_; + std::shared_ptr map_; }; int main(int argc, char **argv) { - rclcpp::init(argc, argv); rclcpp::spin(std::make_shared()); rclcpp::shutdown();