diff --git a/include/grid_map_geo/grid_map_geo.hpp b/include/grid_map_geo/grid_map_geo.hpp index 3dfd8c1..e0fe47c 100644 --- a/include/grid_map_geo/grid_map_geo.hpp +++ b/include/grid_map_geo/grid_map_geo.hpp @@ -40,8 +40,8 @@ // Color map is optional. If left as this default value, color will not be loaded. static const std::string COLOR_MAP_DEFAULT_PATH{""}; -#include #include +#include // #include "transform.hpp" #include "grid_map_geo/transform.hpp" diff --git a/src/grid_map_geo.cpp b/src/grid_map_geo.cpp index 00773f3..1f0914d 100644 --- a/src/grid_map_geo.cpp +++ b/src/grid_map_geo.cpp @@ -67,7 +67,7 @@ * @param corners The returned corners in the geographic coordinates * @return */ -inline bool getGeoCorners(const GDALDatasetUniquePtr& datasetPtr, Corners& corners) { +inline bool getGeoCorners(const GDALDatasetUniquePtr &datasetPtr, Corners &corners) { std::array geoTransform; // https://gdal.org/tutorials/geotransforms_tut.html#introduction-to-geotransforms diff --git a/src/map_publisher.cpp b/src/map_publisher.cpp index 4f9271d..8c001d2 100644 --- a/src/map_publisher.cpp +++ b/src/map_publisher.cpp @@ -37,15 +37,15 @@ * @author Jaeyoung Lim */ -#include -#include - #include +#include + +#include #include #include +#include #include #include -#include #include "grid_map_geo/grid_map_geo.hpp" @@ -71,10 +71,10 @@ class MapPublisher : public rclcpp::Node { max_map_descriptor.integer_range.push_back(max_map_descriptor_int_range); const uint16_t max_map_width = - std::clamp(this->declare_parameter("max_map_width", 1024, max_map_descriptor), + std::clamp(this->declare_parameter("max_map_width", std::numeric_limits::max(), max_map_descriptor), max_map_descriptor_int_range.from_value, max_map_descriptor_int_range.to_value); const uint16_t max_map_height = - std::clamp(this->declare_parameter("max_map_height", 1024, max_map_descriptor), + std::clamp(this->declare_parameter("max_map_height", std::numeric_limits::max(), max_map_descriptor), max_map_descriptor_int_range.from_value, max_map_descriptor_int_range.to_value); RCLCPP_INFO_STREAM(get_logger(), "gdal_dataset_path: '" << gdal_dataset_path << "'");