Skip to content

Commit

Permalink
Default to infinite map size
Browse files Browse the repository at this point in the history
Signed-off-by: Ryan Friedman <[email protected]>
  • Loading branch information
Ryanf55 committed Feb 4, 2024
1 parent b859878 commit db43325
Show file tree
Hide file tree
Showing 3 changed files with 8 additions and 8 deletions.
2 changes: 1 addition & 1 deletion include/grid_map_geo/grid_map_geo.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 <iostream>
#include <geometry_msgs/msg/transform_stamped.hpp>
#include <iostream>

// #include "transform.hpp"
#include "grid_map_geo/transform.hpp"
Expand Down
2 changes: 1 addition & 1 deletion src/grid_map_geo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<double, 6> geoTransform;

// https://gdal.org/tutorials/geotransforms_tut.html#introduction-to-geotransforms
Expand Down
12 changes: 6 additions & 6 deletions src/map_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,15 +37,15 @@
* @author Jaeyoung Lim <[email protected]>
*/

#include <algorithm>
#include <limits>

#include <grid_map_msgs/msg/grid_map.h>
#include <tf2_ros/static_transform_broadcaster.h>

#include <algorithm>
#include <geometry_msgs/msg/transform_stamped.hpp>
#include <grid_map_ros/GridMapRosConverter.hpp>
#include <limits>
#include <rclcpp/rclcpp.hpp>
#include <std_msgs/msg/string.hpp>
#include <tf2_ros/static_transform_broadcaster.h>

#include "grid_map_geo/grid_map_geo.hpp"

Expand All @@ -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<int>::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<int>::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 << "'");
Expand Down

0 comments on commit db43325

Please sign in to comment.