37
37
* @author Jaeyoung Lim <[email protected] >
38
38
*/
39
39
40
- #include < algorithm>
41
- #include < limits>
42
-
43
40
#include < grid_map_msgs/msg/grid_map.h>
41
+ #include < tf2_ros/static_transform_broadcaster.h>
42
+
43
+ #include < algorithm>
44
44
#include < geometry_msgs/msg/transform_stamped.hpp>
45
45
#include < grid_map_ros/GridMapRosConverter.hpp>
46
+ #include < limits>
46
47
#include < rclcpp/rclcpp.hpp>
47
48
#include < std_msgs/msg/string.hpp>
48
- #include < tf2_ros/static_transform_broadcaster.h>
49
49
50
50
#include " grid_map_geo/grid_map_geo.hpp"
51
51
@@ -71,10 +71,10 @@ class MapPublisher : public rclcpp::Node {
71
71
max_map_descriptor.integer_range .push_back (max_map_descriptor_int_range);
72
72
73
73
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),
75
75
max_map_descriptor_int_range.from_value , max_map_descriptor_int_range.to_value );
76
76
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),
78
78
max_map_descriptor_int_range.from_value , max_map_descriptor_int_range.to_value );
79
79
80
80
RCLCPP_INFO_STREAM (get_logger (), " gdal_dataset_path: '" << gdal_dataset_path << " '" );
0 commit comments