|
48 | 48 | using namespace std::chrono_literals;
|
49 | 49 |
|
50 | 50 | class MapPublisher : public rclcpp::Node {
|
51 |
| - public: |
52 |
| - MapPublisher() : Node("map_publisher") { |
53 |
| - original_map_pub_ = this->create_publisher<grid_map_msgs::msg::GridMap>("elevation_map", 1); |
| 51 | + public: |
| 52 | + MapPublisher() : Node("map_publisher") { |
| 53 | + original_map_pub_ = this->create_publisher<grid_map_msgs::msg::GridMap>("elevation_map", 1); |
54 | 54 |
|
55 |
| - std::string file_path = this->declare_parameter("tif_path", "."); |
56 |
| - std::string color_path = this->declare_parameter("tif_color_path", "."); |
| 55 | + std::string file_path = this->declare_parameter("tif_path", "."); |
| 56 | + std::string color_path = this->declare_parameter("tif_color_path", "."); |
57 | 57 |
|
58 |
| - RCLCPP_INFO_STREAM(get_logger(), "file_path " << file_path); |
59 |
| - RCLCPP_INFO_STREAM(get_logger(), "color_path " << color_path); |
| 58 | + RCLCPP_INFO_STREAM(get_logger(), "file_path " << file_path); |
| 59 | + RCLCPP_INFO_STREAM(get_logger(), "color_path " << color_path); |
60 | 60 |
|
61 |
| - map_ = std::make_shared<GridMapGeo>(); |
62 |
| - map_->Load(file_path, false, color_path); |
63 |
| - timer_ = this->create_wall_timer(5s, std::bind(&MapPublisher::timer_callback, this)); |
64 |
| - } |
65 |
| - private: |
66 |
| - void timer_callback() { |
67 |
| - auto msg = grid_map::GridMapRosConverter::toMessage(map_->getGridMap()); |
68 |
| - original_map_pub_->publish(std::move(msg)); |
69 |
| - } |
70 |
| - rclcpp::TimerBase::SharedPtr timer_; |
71 |
| - rclcpp::Publisher<grid_map_msgs::msg::GridMap>::SharedPtr original_map_pub_; |
72 |
| - std::shared_ptr<GridMapGeo> map_; |
| 61 | + map_ = std::make_shared<GridMapGeo>(); |
| 62 | + map_->Load(file_path, false, color_path); |
| 63 | + timer_ = this->create_wall_timer(5s, std::bind(&MapPublisher::timer_callback, this)); |
| 64 | + } |
| 65 | + |
| 66 | + private: |
| 67 | + void timer_callback() { |
| 68 | + auto msg = grid_map::GridMapRosConverter::toMessage(map_->getGridMap()); |
| 69 | + original_map_pub_->publish(std::move(msg)); |
| 70 | + } |
| 71 | + rclcpp::TimerBase::SharedPtr timer_; |
| 72 | + rclcpp::Publisher<grid_map_msgs::msg::GridMap>::SharedPtr original_map_pub_; |
| 73 | + std::shared_ptr<GridMapGeo> map_; |
73 | 74 | };
|
74 | 75 |
|
75 | 76 | int main(int argc, char **argv) {
|
76 |
| - |
77 | 77 | rclcpp::init(argc, argv);
|
78 | 78 | rclcpp::spin(std::make_shared<MapPublisher>());
|
79 | 79 | rclcpp::shutdown();
|
|
0 commit comments