15 #include <OGRE/OgreManualObject.h>
16 #include <OGRE/OgreMaterialManager.h>
17 #include <OGRE/OgreSceneManager.h>
18 #include <OGRE/OgreSceneNode.h>
19 #include <OGRE/OgreTextureManager.h>
20 #include <OGRE/OgreTechnique.h>
22 #include <GeographicLib/UTMUPS.hpp>
42 #include <unordered_map>
70 new RosTopicProperty(
"Topic",
"", QString::fromStdString(ros::message_traits::datatype<sensor_msgs::NavSatFix>()),
71 "sensor_msgs::NavSatFix topic to subscribe to.",
this, SLOT(
updateTopic()));
75 "Whether to transform tiles via map frame and fix messages or via UTM frame",
85 "Map Frame",
"map",
"Frame ID of the map.",
this,
nullptr,
false, SLOT(
updateMapFrame()));
90 "UTM Frame",
"utm",
"Frame ID of the UTM frame.",
this,
nullptr,
false, SLOT(
updateUtmFrame()));
95 new IntProperty(
"UTM Zone", GeographicLib::UTMUPS::STANDARD,
"UTM zone (-1 means autodetect).",
104 "How to determine XY coordinates that define the displayed tiles.",
111 "How to determine height of the displayed tiles.",
124 "Rendering option, controls whether or not the map is always"
125 " drawn behind everything else.",
136 QString
const zoom_desc = QString::fromStdString(
"Zoom level (0 - " + std::to_string(
MAX_ZOOM) +
")");
143 QString
const blocks_desc = QString::fromStdString(
"Adjacent blocks (0 - " + std::to_string(
MAX_BLOCKS) +
")");
286 if (!std::regex_match(tile_url, std::regex(R
"(^(https?:\/\/).*)")))
288 ROS_ERROR("Invalid Object URI: %s", tile_url.c_str());
291 else if (!std::regex_match(tile_url, std::regex(R
"(.*\{([xyz]|lat|lon)\}.*)")))
293 ROS_ERROR("No coordinates ({lat}, {lon} or {x}, {y}, {z}) found in URI: %s", tile_url.c_str());
530 ROS_WARN_THROTTLE(2.0,
"Setting UTM frame '%s' as XY reference is invalid, as the computed easting and "
531 "northing of zero is out of bounds. Select a different frame.",
utm_frame_.c_str());
620 if (!obj.material.isNull())
622 Ogre::MaterialManager::getSingleton().remove(obj.material->getName());
635 for (
int block = 0; block < (2 *
blocks_ + 1) * (2 *
blocks_ + 1); ++block)
638 static size_t count = 0;
639 std::string
const name_suffix = std::to_string(count);
643 Ogre::MaterialPtr material = Ogre::MaterialManager::getSingleton().create(
644 "satellite_material_" + name_suffix, Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME);
645 material->setReceiveShadows(
false);
646 material->getTechnique(0)->setLightingEnabled(
false);
647 material->setDepthBias(-16.0
f, 0.0
f);
648 material->setCullingMode(Ogre::CULL_NONE);
649 material->setDepthWriteEnabled(
false);
652 Ogre::TextureUnitState* tex_unit = material->getTechnique(0)->getPass(0)->createTextureUnitState();
653 tex_unit->setTextureFiltering(Ogre::TFO_BILINEAR);
656 Ogre::ManualObject* obj =
scene_manager_->createManualObject(
"satellite_object_" + name_suffix);
657 obj->setVisible(
false);
660 assert(!material.isNull());
661 objects_.emplace_back(obj, material);
701 reference_wgs = { msg->latitude, msg->longitude };
713 if (
utm_zone_ < GeographicLib::UTMUPS::MINZONE)
718 GeographicLib::UTMUPS::Forward(msg->latitude, msg->longitude, zone, northp, e, n,
utm_zone_);
720 ROS_INFO(
"UTM zone has been automatically determined from NavSatFix message to %s.",
721 GeographicLib::UTMUPS::EncodeZone(zone, northp).c_str());
724 const auto& utm_coords = tf_reference_utm.transform.translation;
725 GeographicLib::UTMUPS::Reverse(
utm_zone_, msg->latitude >= 0, utm_coords.x, utm_coords.y, reference_wgs.lat,
726 reference_wgs.lon,
true);
729 catch (GeographicLib::GeographicErr& err)
751 if (not center_tile_changed)
758 ROS_DEBUG_NAMED(
"rviz_satellite",
"Updating center tile to (%i, %i)", tile_coordinates.
x, tile_coordinates.
y);
790 ROS_DEBUG_NAMED(
"rviz_satellite",
"Requesting new tile images from the server");
794 catch (std::exception
const& e)
805 if (error_rate > 0.95)
807 setStatus(StatusProperty::Level::Error,
"TileRequest",
"Few or no tiles received");
809 else if (error_rate > 0.3)
811 setStatus(StatusProperty::Level::Warn,
"TileRequest",
812 "Not all requested tiles have been received. Possibly the server is throttling?");
816 setStatus(StatusProperty::Level::Ok,
"TileRequest",
"OK");
849 bool all_tiles_loaded =
true;
856 auto obj = it->object;
857 auto& material = it->material;
858 assert(!material.isNull());
867 obj->setVisible(
false);
868 all_tiles_loaded =
false;
872 obj->setVisible(
true);
875 Ogre::TextureUnitState* tex_unit = material->getTechnique(0)->getPass(0)->getTextureUnitState(0);
876 tex_unit->setTextureName(tile->
texture->getName());
882 material->setSceneBlending(Ogre::SBT_REPLACE);
886 material->setSceneBlending(Ogre::SBT_TRANSPARENT_ALPHA);
887 material->setDepthWriteEnabled(
false);
893 obj->setRenderQueueGroup(Ogre::RENDER_QUEUE_3);
897 obj->setRenderQueueGroup(Ogre::RENDER_QUEUE_MAIN);
900 tex_unit->setAlphaOperation(Ogre::LBX_SOURCE1, Ogre::LBS_MANUAL, Ogre::LBS_CURRENT,
alpha_);
913 double const x = (xx -
center_tile_->coord.x) * tile_w_h_m;
915 double const y = -(yy -
center_tile_->coord.y) * tile_w_h_m;
921 obj->begin(material->getName(), Ogre::RenderOperation::OT_TRIANGLE_LIST);
930 obj->position(x, y, 0.0
f);
931 obj->textureCoord(0.0
f, 0.0
f);
932 obj->normal(0.0
f, 0.0
f, 1.0
f);
935 obj->position(x + tile_w_h_m, y + tile_w_h_m, 0.0
f);
936 obj->textureCoord(1.0
f, 1.0
f);
937 obj->normal(0.0
f, 0.0
f, 1.0
f);
940 obj->position(x, y + tile_w_h_m, 0.0
f);
941 obj->textureCoord(0.0
f, 1.0
f);
942 obj->normal(0.0
f, 0.0
f, 1.0
f);
945 obj->position(x, y, 0.0
f);
946 obj->textureCoord(0.0
f, 0.0
f);
947 obj->normal(0.0
f, 0.0
f, 1.0
f);
950 obj->position(x + tile_w_h_m, y, 0.0
f);
951 obj->textureCoord(1.0
f, 0.0
f);
952 obj->normal(0.0
f, 0.0
f, 1.0
f);
955 obj->position(x + tile_w_h_m, y + tile_w_h_m, 0.0
f);
956 obj->textureCoord(1.0
f, 1.0
f);
957 obj->normal(0.0
f, 0.0
f, 1.0
f);
964 if (!all_tiles_loaded)
1010 tf2::Vector3 t_navsat_map;
1016 auto const tf_navsat_map =
1018 tf2::fromMsg(tf_navsat_map.transform.translation, t_navsat_map);
1027 auto const tf_navsat_map =
1029 tf2::fromMsg(tf_navsat_map.transform.translation, t_navsat_map);
1040 auto const ref_fix_tile_coords = fromWGSCoordinate<double>(*
ref_coords_,
zoom_);
1045 auto const center_tile_offset_x = ref_fix_tile_coords.x - std::floor(ref_fix_tile_coords.x);
1048 auto const center_tile_offset_y = 1 - (ref_fix_tile_coords.y - std::floor(ref_fix_tile_coords.y));
1051 ROS_DEBUG_NAMED(
"rviz_satellite",
"Tile resolution is %.1fm", tile_w_h_m);
1054 tf2::Vector3 t_centertile_navsat = { center_tile_offset_x * tile_w_h_m, center_tile_offset_y * tile_w_h_m, 0 };
1073 auto const tileWGS = toWGSCoordinate<int>(tile,
zoom_);
1076 double northing, easting;
1082 GeographicLib::UTMUPS::Forward(tileWGS.lat, tileWGS.lon, utm_zone, northp, easting, northing,
utm_zone_);
1084 catch (GeographicLib::GeographicErr& err)
1087 if (
utm_zone_ != GeographicLib::UTMUPS::STANDARD)
1091 GeographicLib::UTMUPS::Forward(tileWGS.lat, tileWGS.lon, utm_zone, northp, easting, northing,
1092 GeographicLib::UTMUPS::STANDARD);
1095 catch (GeographicLib::GeographicErr& err)
1112 ROS_INFO(
"UTM zone has been updated to %s.", GeographicLib::UTMUPS::EncodeZone(utm_zone, northp).c_str());
1136 auto const tf_reference_utm =
1164 auto const tf_reference_utm =
1171 const auto& utm_coords = tf_reference_utm.transform.translation;
1172 GeographicLib::UTMUPS::Reverse(
utm_zone_,
ref_fix_->latitude >= 0, utm_coords.x, utm_coords.y, reference_wgs.lat,
1173 reference_wgs.lon,
true);
1176 auto new_fix = boost::make_shared<sensor_msgs::NavSatFix>();
1179 new_fix->latitude = reference_wgs.lat;
1180 new_fix->longitude = reference_wgs.lon;
1181 new_fix->altitude = utm_coords.z;
1191 catch (GeographicLib::GeographicErr& err)
1209 Ogre::Quaternion o_centertile_fixed;
1211 Ogre::Vector3 t_centertile_fixed;
1215 const auto& frame_name =
header.frame_id;
1242 QString::fromStdString(
"Could not transform from [" + frame_name +
"] to Fixed Frame [" +
1243 fixed_frame_.toStdString() +
"] for an unknown reason"));