43
43
#include < grid_map_core/iterators/CircleIterator.hpp>
44
44
#include < grid_map_core/iterators/GridMapIterator.hpp>
45
45
46
- GridMapGeo::GridMapGeo () {}
46
+ #include < geometry_msgs/TransformStamped.h>
47
+ #include < tf2_ros/static_transform_broadcaster.h>
48
+
49
+ GridMapGeo::GridMapGeo (const std::string frame_id) { frame_id_ = frame_id; }
47
50
48
51
GridMapGeo::~GridMapGeo () {}
49
52
50
- bool GridMapGeo::Load (const std::string &map_path, bool algin_terrain, const std::string color_map_path) {
51
- bool loaded = initializeFromGeotiff (map_path, algin_terrain );
53
+ bool GridMapGeo::Load (const std::string &map_path, const std::string color_map_path) {
54
+ bool loaded = initializeFromGeotiff (map_path);
52
55
if (!color_map_path.empty ()) { // Load color layer if the color path is nonempty
53
56
bool color_loaded = addColorFromGeotiff (color_map_path);
54
57
}
55
58
if (!loaded) return false ;
56
59
return true ;
57
60
}
58
61
59
- bool GridMapGeo::initializeFromGeotiff (const std::string &path, bool align_terrain ) {
62
+ bool GridMapGeo::initializeFromGeotiff (const std::string &path) {
60
63
GDALAllRegister ();
61
64
GDALDataset *dataset = (GDALDataset *)GDALOpen (path.c_str (), GA_ReadOnly);
62
65
if (!dataset) {
@@ -80,6 +83,8 @@ bool GridMapGeo::initializeFromGeotiff(const std::string &path, bool align_terra
80
83
const char *pszProjection = dataset->GetProjectionRef ();
81
84
std::cout << std::endl << " Wkt ProjectionRef: " << pszProjection << std::endl;
82
85
86
+ const OGRSpatialReference *spatial_ref = dataset->GetSpatialRef ();
87
+ std::string name_coordinate = spatial_ref->GetAttrValue (" geogcs" );
83
88
// Get image metadata
84
89
unsigned width = dataset->GetRasterXSize ();
85
90
unsigned height = dataset->GetRasterYSize ();
@@ -99,24 +104,9 @@ bool GridMapGeo::initializeFromGeotiff(const std::string &path, bool align_terra
99
104
100
105
Eigen::Vector2d position{Eigen::Vector2d::Zero ()};
101
106
102
- // / TODO: Generalize to set local origin as center of map position
103
- // Eigen::Vector3d origin_lv03 =
104
- // transformCoordinates(ESPG::WGS84, std::string(pszProjection), localorigin_wgs84_.position);
105
- // localorigin_e_ = origin_lv03(0);
106
- // localorigin_n_ = origin_lv03(1);
107
- // localorigin_altitude_ = origin_lv03(2);
108
- // if (align_terrain) {
109
- // std::cout << "[GridMapGeo] Aligning terrain!" << std::endl;
110
- // double map_position_x = mapcenter_e - localorigin_e_;
111
- // double map_position_y = mapcenter_n - localorigin_n_;
112
- // position = Eigen::Vector2d(map_position_x, map_position_y);
113
- // } else {
114
- // std::cout << "[GridMapGeo] Not aligning terrain!" << std::endl;
115
- // }
116
-
117
107
grid_map_.setGeometry (length, resolution, position);
118
108
// / TODO: Use TF for geocoordinates
119
- grid_map_.setFrameId (" map " );
109
+ grid_map_.setFrameId (frame_id_ );
120
110
grid_map_.add (" elevation" );
121
111
GDALRasterBand *elevationBand = dataset->GetRasterBand (1 );
122
112
@@ -133,17 +123,21 @@ bool GridMapGeo::initializeFromGeotiff(const std::string &path, bool align_terra
133
123
layer_elevation (x, y) = data[gridMapIndex (0 ) + width * gridMapIndex (1 )];
134
124
}
135
125
136
- // / TODO: This is a workaround with the problem of gdal 3 not translating altitude correctly.
137
- // / This section just levels the current position to the ground
138
- double altitude{0.0 };
139
- if (grid_map_.isInside (Eigen::Vector2d (0.0 , 0.0 ))) {
140
- altitude = grid_map_.atPosition (" elevation" , Eigen::Vector2d (0.0 , 0.0 ));
141
- }
126
+ static tf2_ros::StaticTransformBroadcaster static_broadcaster;
127
+ geometry_msgs::TransformStamped static_transformStamped;
128
+
129
+ static_transformStamped.header .stamp = ros::Time::now ();
130
+ static_transformStamped.header .frame_id = name_coordinate;
131
+ static_transformStamped.child_frame_id = frame_id_;
132
+ static_transformStamped.transform .translation .x = mapcenter_e;
133
+ static_transformStamped.transform .translation .y = mapcenter_n;
134
+ static_transformStamped.transform .translation .z = 0.0 ;
135
+ static_transformStamped.transform .rotation .x = 0.0 ;
136
+ static_transformStamped.transform .rotation .y = 0.0 ;
137
+ static_transformStamped.transform .rotation .z = 0.0 ;
138
+ static_transformStamped.transform .rotation .w = 1.0 ;
139
+ static_broadcaster.sendTransform (static_transformStamped);
142
140
143
- // Eigen::Translation3d meshlab_translation(0.0, 0.0, -altitude);
144
- // Eigen::AngleAxisd meshlab_rotation(Eigen::AngleAxisd::Identity());
145
- // Eigen::Isometry3d transform = meshlab_translation * meshlab_rotation; // Apply affine transformation.
146
- // grid_map_ = grid_map_.getTransformedMap(transform, "elevation", grid_map_.getFrameId(), true);
147
141
return true ;
148
142
}
149
143
0 commit comments