|
| 1 | +/**************************************************************************** |
| 2 | + * |
| 3 | + * Copyright (c) 2021 Jaeyoung Lim. All rights reserved. |
| 4 | + * |
| 5 | + * Redistribution and use in source and binary forms, with or without |
| 6 | + * modification, are permitted provided that the following conditions |
| 7 | + * are met: |
| 8 | + * |
| 9 | + * 1. Redistributions of source code must retain the above copyright |
| 10 | + * notice, this list of conditions and the following disclaimer. |
| 11 | + * 2. Redistributions in binary form must reproduce the above copyright |
| 12 | + * notice, this list of conditions and the following disclaimer in |
| 13 | + * the documentation and/or other materials provided with the |
| 14 | + * distribution. |
| 15 | + * 3. Neither the name PX4 nor the names of its contributors may be |
| 16 | + * used to endorse or promote products derived from this software |
| 17 | + * without specific prior written permission. |
| 18 | + * |
| 19 | + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
| 20 | + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
| 21 | + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
| 22 | + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
| 23 | + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
| 24 | + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
| 25 | + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
| 26 | + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
| 27 | + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
| 28 | + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
| 29 | + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
| 30 | + * POSSIBILITY OF SUCH DAMAGE. |
| 31 | + * |
| 32 | + ****************************************************************************/ |
| 33 | +/** |
| 34 | + * @brief Node to test planner in the view utiltiy map |
| 35 | + * |
| 36 | + * |
| 37 | + * @author Jaeyoung Lim <[email protected]> |
| 38 | + */ |
| 39 | + |
| 40 | +#include <grid_map_geo/grid_map_geo.h> |
| 41 | +#include <grid_map_msgs/GridMap.h> |
| 42 | +#include <ros/ros.h> |
| 43 | +#include <grid_map_ros/GridMapRosConverter.hpp> |
| 44 | + |
| 45 | +#include <gdal/ogr_spatialref.h> |
| 46 | + |
| 47 | +constexpr int ESPG_WGS84 = 4326; |
| 48 | +constexpr int ESPG_CH1903_LV03 = 21781; |
| 49 | + |
| 50 | +void transformCoordinates(int src_coord, const double &x, const double &y, const double &z, int tgt_coord, double &x_t, |
| 51 | + double &y_t, double &z_t) { |
| 52 | + OGRSpatialReference source, target; |
| 53 | + source.importFromEPSG(src_coord); |
| 54 | + target.importFromEPSG(tgt_coord); |
| 55 | + |
| 56 | + OGRPoint p; |
| 57 | + p.setX(x); |
| 58 | + p.setY(y); |
| 59 | + p.setZ(z); |
| 60 | + p.assignSpatialReference(&source); |
| 61 | + |
| 62 | + p.transformTo(&target); |
| 63 | + x_t = p.getX(); |
| 64 | + y_t = p.getY(); |
| 65 | + z_t = p.getZ(); |
| 66 | + return; |
| 67 | +} |
| 68 | + |
| 69 | +void LoadTerrainFromVrt(std::string path, const Eigen::Vector3d &query_position, const Eigen::Vector2d &offset, |
| 70 | + grid_map::GridMap &map, grid_map::GridMap &vrt_map_object) { |
| 71 | + std::shared_ptr<GridMapGeo> vrt_map = std::make_shared<GridMapGeo>(); |
| 72 | + |
| 73 | + Eigen::Vector3d query_position_lv03 = query_position; |
| 74 | + /// Convert LV03 to WGS84 |
| 75 | + Eigen::Vector3d map_center_wgs84; // Map center in WGS84 |
| 76 | + transformCoordinates(ESPG_CH1903_LV03, query_position_lv03(0), query_position_lv03(1), query_position_lv03(2), |
| 77 | + ESPG_WGS84, map_center_wgs84.x(), map_center_wgs84.y(), map_center_wgs84.z()); |
| 78 | + |
| 79 | + std::cout << "Loading VRT Map:" << std::endl; |
| 80 | + std::cout << " - map_center_wgs84:" << map_center_wgs84.transpose() << std::endl; |
| 81 | + /// TODO: Discover extent from corners |
| 82 | + Eigen::Vector2d extent_wgs84(0.5, 0.5); |
| 83 | + vrt_map->initializeFromVrt(path, map_center_wgs84.head(2), extent_wgs84); |
| 84 | + std::cout << " - Success!" << std::endl; |
| 85 | + |
| 86 | + /// TODO: Loaded VRT map |
| 87 | + std::cout << "Reprojecting map" << std::endl; |
| 88 | + Eigen::Vector2d extent_lv03(12000.0, 12000.0); |
| 89 | + double resolution{100.0}; |
| 90 | + Eigen::Vector2d position{Eigen::Vector2d::Zero()}; |
| 91 | + map.setGeometry(extent_lv03, resolution, position); |
| 92 | + map.add("elevation"); |
| 93 | + map.setFrameId("map"); |
| 94 | + for (grid_map::GridMapIterator iterator(map); !iterator.isPastEnd(); ++iterator) { |
| 95 | + const grid_map::Index index = *iterator; |
| 96 | + Eigen::Vector2d cell_position; // Position of cell relative to map coordinates |
| 97 | + map.getPosition(index, cell_position); |
| 98 | + auto cell_position_lv03 = cell_position + query_position_lv03.head(2); // Position of cell in CH1903/LV03 |
| 99 | + double dummy; |
| 100 | + Eigen::Vector2d cell_position_wgs84; |
| 101 | + transformCoordinates(ESPG_CH1903_LV03, cell_position_lv03(0), cell_position_lv03(1), cell_position_lv03(2), |
| 102 | + ESPG_WGS84, cell_position_wgs84.x(), cell_position_wgs84.y(), dummy); |
| 103 | + // std::cout << " - cell_position_wgs84:" << cell_position_wgs84.transpose() << std::endl; |
| 104 | + |
| 105 | + Eigen::Vector2d local_wgs84 = cell_position_wgs84 - map_center_wgs84.head(2); |
| 106 | + double tmp = local_wgs84(0); |
| 107 | + local_wgs84(0) = local_wgs84(1); |
| 108 | + local_wgs84(1) = tmp; |
| 109 | + // std::cout << " - local_wgs84:" << local_wgs84.transpose() << std::endl; |
| 110 | + auto elevation = vrt_map->getGridMap().atPosition("elevation", local_wgs84); |
| 111 | + map.atPosition("elevation", cell_position) = elevation; |
| 112 | + } |
| 113 | + map.setPosition(offset); |
| 114 | + vrt_map_object = vrt_map->getGridMap(); |
| 115 | +} |
| 116 | + |
| 117 | +int main(int argc, char **argv) { |
| 118 | + ros::init(argc, argv, "terrain_loader"); |
| 119 | + ros::NodeHandle nh(""); |
| 120 | + ros::NodeHandle nh_private("~"); |
| 121 | + |
| 122 | + ros::Publisher map_pub = nh.advertise<grid_map_msgs::GridMap>("grid_map", 1, true); |
| 123 | + ros::Publisher map_pub2 = nh.advertise<grid_map_msgs::GridMap>("grid_map2", 1, true); |
| 124 | + |
| 125 | + std::string path; |
| 126 | + nh_private.param<std::string>("terrain_path", path, "resources/cadastre.tif"); |
| 127 | + |
| 128 | + Eigen::Vector3d test_position = Eigen::Vector3d(783199.15, 187585.10, 0.0); |
| 129 | + |
| 130 | + for (int i = 0; i < 4; i++) { |
| 131 | + Eigen::Vector3d offset = static_cast<double>(i) * Eigen::Vector3d(2500.0, 2500.0, 0.0); |
| 132 | + Eigen::Vector3d query_position = test_position + offset; |
| 133 | + |
| 134 | + grid_map::GridMap map; |
| 135 | + grid_map::GridMap vrt_map; |
| 136 | + LoadTerrainFromVrt(path, query_position, offset.head(2), map, vrt_map); |
| 137 | + std::cout << "i: " << i << " offset: " << offset.transpose() << std::endl; |
| 138 | + |
| 139 | + grid_map_msgs::GridMap msg; |
| 140 | + grid_map::GridMapRosConverter::toMessage(map, msg); |
| 141 | + map_pub.publish(msg); |
| 142 | + |
| 143 | + grid_map_msgs::GridMap msg2; |
| 144 | + grid_map::GridMapRosConverter::toMessage(vrt_map, msg2); |
| 145 | + map_pub2.publish(msg2); |
| 146 | + } |
| 147 | + |
| 148 | + ros::spin(); |
| 149 | + return 0; |
| 150 | +} |
0 commit comments