Skip to content

Commit db43325

Browse files
committed
Default to infinite map size
Signed-off-by: Ryan Friedman <[email protected]>
1 parent b859878 commit db43325

File tree

3 files changed

+8
-8
lines changed

3 files changed

+8
-8
lines changed

include/grid_map_geo/grid_map_geo.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -40,8 +40,8 @@
4040
// Color map is optional. If left as this default value, color will not be loaded.
4141
static const std::string COLOR_MAP_DEFAULT_PATH{""};
4242

43-
#include <iostream>
4443
#include <geometry_msgs/msg/transform_stamped.hpp>
44+
#include <iostream>
4545

4646
// #include "transform.hpp"
4747
#include "grid_map_geo/transform.hpp"

src/grid_map_geo.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -67,7 +67,7 @@
6767
* @param corners The returned corners in the geographic coordinates
6868
* @return
6969
*/
70-
inline bool getGeoCorners(const GDALDatasetUniquePtr& datasetPtr, Corners& corners) {
70+
inline bool getGeoCorners(const GDALDatasetUniquePtr &datasetPtr, Corners &corners) {
7171
std::array<double, 6> geoTransform;
7272

7373
// https://gdal.org/tutorials/geotransforms_tut.html#introduction-to-geotransforms

src/map_publisher.cpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -37,15 +37,15 @@
3737
* @author Jaeyoung Lim <[email protected]>
3838
*/
3939

40-
#include <algorithm>
41-
#include <limits>
42-
4340
#include <grid_map_msgs/msg/grid_map.h>
41+
#include <tf2_ros/static_transform_broadcaster.h>
42+
43+
#include <algorithm>
4444
#include <geometry_msgs/msg/transform_stamped.hpp>
4545
#include <grid_map_ros/GridMapRosConverter.hpp>
46+
#include <limits>
4647
#include <rclcpp/rclcpp.hpp>
4748
#include <std_msgs/msg/string.hpp>
48-
#include <tf2_ros/static_transform_broadcaster.h>
4949

5050
#include "grid_map_geo/grid_map_geo.hpp"
5151

@@ -71,10 +71,10 @@ class MapPublisher : public rclcpp::Node {
7171
max_map_descriptor.integer_range.push_back(max_map_descriptor_int_range);
7272

7373
const uint16_t max_map_width =
74-
std::clamp(this->declare_parameter("max_map_width", 1024, max_map_descriptor),
74+
std::clamp(this->declare_parameter("max_map_width", std::numeric_limits<int>::max(), max_map_descriptor),
7575
max_map_descriptor_int_range.from_value, max_map_descriptor_int_range.to_value);
7676
const uint16_t max_map_height =
77-
std::clamp(this->declare_parameter("max_map_height", 1024, max_map_descriptor),
77+
std::clamp(this->declare_parameter("max_map_height", std::numeric_limits<int>::max(), max_map_descriptor),
7878
max_map_descriptor_int_range.from_value, max_map_descriptor_int_range.to_value);
7979

8080
RCLCPP_INFO_STREAM(get_logger(), "gdal_dataset_path: '" << gdal_dataset_path << "'");

0 commit comments

Comments
 (0)