.. _program_listing_file_src_tile.hpp: Program Listing for File tile.hpp ================================= |exhale_lsh| :ref:`Return to documentation for file ` (``src/tile.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp /* Copyright 2018-2019 TomTom N.V., 2014 Gareth Cross Licensed under the Apache License, Version 2.0 (the "License"); you may not use this file except in compliance with the License. You may obtain a copy of the License at http://www.apache.org/licenses/LICENSE-2.0 Unless required by applicable law or agreed to in writing, software distributed under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and limitations under the License. */ #pragma once #include #include #include #include #include #include #include #include namespace rviz_satellite { struct TileCoordinate { int x, y, z; bool operator==(const TileCoordinate & other) const { return std::tie(x, y, z) == std::tie(other.x, other.y, other.z); } bool operator!=(const TileCoordinate & other) const { return std::tie(x, y, z) != std::tie(other.x, other.y, other.z); } bool operator<(const TileCoordinate & other) const { return std::tie(x, y, z) < std::tie(other.x, other.y, other.z); } }; struct TileId { std::string server_url; TileCoordinate coord; bool operator==(const TileId & other) const { return std::tie(coord, server_url) == std::tie(other.coord, other.server_url); } bool operator<(const TileId & other) const { return std::tie(coord, server_url) < std::tie(other.coord, other.server_url); } }; struct TileMapInformation { int zoom; // local map information bool local_map; double meter_per_pixel_z0; double origin_x; double origin_y; std::string origin_crs; // local map projection PJ_CONTEXT * context = proj_context_create(); PJ * transformation = nullptr; }; static constexpr int MAX_BLOCKS = 8; static constexpr int MAX_ZOOM = 22; double zoomSize(double lat, TileMapInformation tile_map_info); std::string tileURL(const TileId & tile_id); TileCoordinate fromWGS(const sensor_msgs::msg::NavSatFix &, TileMapInformation tile_map_info); Ogre::Vector2 tileOffset(const sensor_msgs::msg::NavSatFix &, TileMapInformation tile_map_info); } // namespace rviz_satellite std::ostream & operator<<(std::ostream & os, const rviz_satellite::TileId & tile_id); // Make type available for QVariant, which is required to use it as network request data Q_DECLARE_METATYPE(rviz_satellite::TileId)