aerialmap_display.cpp
Go to the documentation of this file.
1 /* Copyright 2014 Gareth Cross
2 
3 Licensed under the Apache License, Version 2.0 (the "License");
4 you may not use this file except in compliance with the License.
5 You may obtain a copy of the License at
6 
7 http://www.apache.org/licenses/LICENSE-2.0
8 
9 Unless required by applicable law or agreed to in writing, software
10 distributed under the License is distributed on an "AS IS" BASIS,
11 WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 See the License for the specific language governing permissions and
13 limitations under the License. */
14 
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>
21 
22 #include <GeographicLib/UTMUPS.hpp>
23 
24 #include "rviz/display_context.h"
25 #include "rviz/frame_manager.h"
33 
34 #include <tf2/LinearMath/Vector3.h>
36 
37 #include "aerialmap_display.h"
38 #include "mercator.h"
40 
41 #include <regex>
42 #include <unordered_map>
43 
44 
45 namespace rviz
46 {
59 std::unordered_map<MapTransformType, QString> mapTransformTypeStrings =
60 {
61  {MapTransformType::VIA_MAP_FRAME, "NavSatFix Messages and Map Frame"},
62  {MapTransformType::VIA_UTM_FRAME, "Explicit UTM Frame"},
63 };
64 
66 {
67  center_tile_pose_.pose.orientation.w = 1;
68 
70  new RosTopicProperty("Topic", "", QString::fromStdString(ros::message_traits::datatype<sensor_msgs::NavSatFix>()),
71  "sensor_msgs::NavSatFix topic to subscribe to.", this, SLOT(updateTopic()));
72 
74  new EnumProperty("Map transform type", mapTransformTypeStrings[MapTransformType::VIA_MAP_FRAME],
75  "Whether to transform tiles via map frame and fix messages or via UTM frame",
76  this, SLOT(updateMapTransformType()));
77  map_transform_type_property_->addOption(mapTransformTypeStrings[MapTransformType::VIA_MAP_FRAME],
78  static_cast<int>(MapTransformType::VIA_MAP_FRAME));
80  static_cast<int>(MapTransformType::VIA_UTM_FRAME));
83 
85  "Map Frame", "map", "Frame ID of the map.", this, nullptr, false, SLOT(updateMapFrame()));
88 
90  "UTM Frame", "utm", "Frame ID of the UTM frame.", this, nullptr, false, SLOT(updateUtmFrame()));
93 
95  new IntProperty("UTM Zone", GeographicLib::UTMUPS::STANDARD, "UTM zone (-1 means autodetect).",
96  this, SLOT(updateUtmZone()));
97  utm_zone_property_->setMin(GeographicLib::UTMUPS::STANDARD);
98  utm_zone_property_->setMax(GeographicLib::UTMUPS::MAXZONE);
101 
104  "How to determine XY coordinates that define the displayed tiles.",
105  this, nullptr, SLOT(updateXYReference()));
108 
111  "How to determine height of the displayed tiles.",
112  this, nullptr, SLOT(updateZReference()));
115 
117  new FloatProperty("Alpha", 0.7, "Amount of transparency to apply to the map.", this, SLOT(updateAlpha()));
121  alpha_ = alpha_property_->getValue().toFloat();
122 
123  draw_under_property_ = new Property("Draw Behind", false,
124  "Rendering option, controls whether or not the map is always"
125  " drawn behind everything else.",
126  this, SLOT(updateDrawUnder()));
129 
130  // properties for map
132  new StringProperty("Object URI", "", "URL from which to retrieve map tiles.", this, SLOT(updateTileUrl()));
135 
136  QString const zoom_desc = QString::fromStdString("Zoom level (0 - " + std::to_string(MAX_ZOOM) + ")");
137  zoom_property_ = new IntProperty("Zoom", 16, zoom_desc, this, SLOT(updateZoom()));
142 
143  QString const blocks_desc = QString::fromStdString("Adjacent blocks (0 - " + std::to_string(MAX_BLOCKS) + ")");
144  blocks_property_ = new IntProperty("Blocks", 3, blocks_desc, this, SLOT(updateBlocks()));
149 
151  new FloatProperty("Z Offset", 0.0, "Offset in Z direction (in meters).", this, SLOT(updateZOffset()));
153  z_offset_ = z_offset_property_->getValue().toFloat();
154 
158 }
159 
161 {
162  unsubscribe();
163  clearAll();
164 }
165 
167 {
174 }
175 
177 {
179  subscribe();
180 }
181 
183 {
184  unsubscribe();
185  clearAll();
186 }
187 
189 {
190  if (!isEnabled())
191  {
192  return;
193  }
194 
195  if (!topic_property_->getTopic().isEmpty())
196  {
197  try
198  {
199  ROS_INFO("Subscribing to %s", topic_property_->getTopicStd().c_str());
202 
203  setStatus(StatusProperty::Ok, "Topic", "OK");
204  }
205  catch (ros::Exception& e)
206  {
207  setStatus(StatusProperty::Error, "Topic", QString("Error subscribing: ") + e.what());
208  }
209  }
210 }
211 
213 {
215 }
216 
218 {
219  // if draw_under_ texture property changed, we need to
220  // - repaint textures
221  // we don't need to
222  // - query textures
223  // - re-create tile grid geometry
224  // - update the center tile
225  // - update transforms
226 
227  auto const alpha = alpha_property_->getFloat();
228  if (alpha == alpha_)
229  {
230  return;
231  }
232 
233  alpha_ = alpha;
234 
235  if (!isEnabled())
236  {
237  return;
238  }
239 
241 }
242 
244 {
245  // if draw_under_ texture property changed, we need to
246  // - repaint textures
247  // we don't need to
248  // - query textures
249  // - re-create tile grid geometry
250  // - update the center tile
251  // - update transforms
252 
253  auto const draw_under = draw_under_property_->getValue().toBool();
254  if (draw_under == draw_under_)
255  {
256  return;
257  }
258 
259  draw_under_ = draw_under;
260 
261  if (!isEnabled())
262  {
263  return;
264  }
265 
267 }
268 
270 {
271  // if the tile url changed, we need to
272  // - query textures
273  // - repaint textures
274  // we don't need to
275  // - re-create tile grid geometry
276  // - update the center tile
277  // - update transforms
278 
279  auto const tile_url = tile_url_property_->getStdString();
280  if (tile_url == tile_url_)
281  {
282  return;
283  }
284 
285  // Check for valid url: https://stackoverflow.com/a/38608262
286  if (!std::regex_match(tile_url, std::regex(R"(^(https?:\/\/).*)")))
287  {
288  ROS_ERROR("Invalid Object URI: %s", tile_url.c_str());
289  // Still setting the url since keeping the old is probably unexpected
290  }
291  else if (!std::regex_match(tile_url, std::regex(R"(.*\{([xyz]|lat|lon)\}.*)")))
292  {
293  ROS_ERROR("No coordinates ({lat}, {lon} or {x}, {y}, {z}) found in URI: %s", tile_url.c_str());
294  }
295 
296  tile_url_ = tile_url;
297 
298  if (!isEnabled())
299  {
300  return;
301  }
302 
304 }
305 
307 {
308  // if the zoom changed, we need to
309  // - re-create tile grid geometry
310  // - update the center tile
311  // - query textures
312  // - repaint textures
313  // - update transforms
314 
315  auto const zoom = zoom_property_->getInt();
316  if (zoom == zoom_)
317  {
318  return;
319  }
320 
321  zoom_ = zoom;
322 
323  if (!isEnabled())
324  {
325  return;
326  }
327 
329 
330  if (ref_fix_)
331  {
333  }
334 }
335 
337 {
338  // if the number of blocks changed, we need to
339  // - re-create tile grid geometry
340  // - query textures
341  // - repaint textures
342  // we don't need to
343  // - update the center tile
344  // - update transforms
345 
346  auto const blocks = blocks_property_->getInt();
347  if (blocks == blocks_)
348  {
349  return;
350  }
351 
352  blocks_ = blocks;
353 
354  if (!isEnabled())
355  {
356  return;
357  }
358 
361 }
362 
364 {
365  // if the NavSat topic changes, we reset everything
366 
367  if (!isEnabled())
368  {
369  return;
370  }
371 
372  unsubscribe();
373  clearAll();
375  subscribe();
376 }
377 
379 {
380  // if the map transform type changed, we need to
381  // - enable/disable map/utm frame inputs
382  // - update XY and Z reference settings to only use values valid for the given mode
383  // - query textures
384  // - repaint textures
385  // - reset and update the center tile
386  // - update transforms
387  // we don't need to
388  // - re-create tile grid geometry
389 
390  auto const map_transform_type = static_cast<MapTransformType>(map_transform_type_property_->getOptionInt());
391 
392  map_transform_type_ = map_transform_type;
393 
394  switch (map_transform_type_)
395  {
400  break;
405  break;
406  }
407 
410 
411  if (ref_fix_)
412  {
414  }
415 }
416 
418 {
419  // if the map frame changed, we need to
420  // - query textures
421  // - repaint textures
422  // - reset and update the center tile
423  // - update transforms
424  // we don't need to
425  // - re-create tile grid geometry
426 
427  auto const map_frame = map_frame_property_->getFrameStd();
428  if (map_frame == map_frame_)
429  {
430  return;
431  }
432 
433  map_frame_ = map_frame;
434 
435  if (!isEnabled())
436  {
437  return;
438  }
439 
440  if (ref_fix_)
441  {
443  }
444 }
445 
447 {
448  // if the UTM frame changed, we need to
449  // - query textures
450  // - repaint textures
451  // - reset and update the center tile
452  // - update transforms
453  // we don't need to
454  // - re-create tile grid geometry
455 
456  auto const utm_frame = utm_frame_property_->getFrameStd();
457  if (utm_frame == utm_frame_)
458  {
459  return;
460  }
461 
462  utm_frame_ = utm_frame;
463 
464  if (!isEnabled())
465  {
466  return;
467  }
468 
469  if (ref_fix_)
470  {
472  }
473 }
474 
476 {
477  // if the UTM zone changed, we need to
478  // - query textures
479  // - repaint textures
480  // - reset and update the center tile
481  // - update transforms
482  // we don't need to
483  // - re-create tile grid geometry
484 
485  auto const utm_zone = utm_zone_property_->getInt();
486  if (utm_zone == utm_zone_)
487  {
488  return;
489  }
490 
491  utm_zone_ = utm_zone;
492 
493  if (!isEnabled())
494  {
495  return;
496  }
497 
498  if (ref_fix_)
499  {
501  }
502 }
503 
505 {
506  // if the XY reference changed, we need to
507  // - query textures
508  // - repaint textures
509  // - reset and update the center tile
510  // - update transforms
511  // we don't need to
512  // - re-create tile grid geometry
513 
514  const auto old_reference_type = xy_reference_type_;
515  const auto old_reference_frame = xy_reference_frame_;
516 
517  switch (map_transform_type_)
518  {
521  xy_reference_frame_ = "";
523  break;
529  {
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());
532  }
533  break;
534  }
535 
536  if (!isEnabled() || (old_reference_type == xy_reference_type_ && old_reference_frame == xy_reference_frame_))
537  {
538  return;
539  }
540 
542  {
543  deleteStatus("UTM");
544  deleteStatus("XY Reference Transform");
545  deleteStatus("XY reference UTM conversion");
546  }
547 
548  if (ref_fix_)
549  {
551  }
552 }
553 
555 {
556  // if the Z reference changed, we need to
557  // - update transforms
558  // we don't need to
559  // - re-create tile grid geometry
560  // - query textures
561  // - repaint textures
562  // - reset and update the center tile
563 
564  const auto old_reference_type = z_reference_type_;
565  const auto old_reference_frame = z_reference_frame_;
566 
567  switch (map_transform_type_)
568  {
571  z_reference_frame_ = "";
573  break;
578  break;
579  }
580 
581  if (!isEnabled() || (old_reference_type == z_reference_type_ && old_reference_frame == z_reference_frame_))
582  {
583  return;
584  }
585 
587  {
588  deleteStatus("Z Reference Transform");
589  }
590 
592 }
593 
595 {
596  // if the Z offset changed, we don't need to do anything as the value is directly read in each update() call
597 
599 }
600 
602 {
603  ref_fix_ = nullptr;
604  center_tile_ = boost::none;
605  ref_coords_ = boost::none;
607 
608  setStatus(StatusProperty::Warn, "Message", "No NavSatFix message received yet");
609 }
610 
612 {
613  for (MapObject& obj : objects_)
614  {
615  // destroy object
616  scene_node_->detachObject(obj.object);
617  scene_manager_->destroyManualObject(obj.object);
618 
619  // destroy material
620  if (!obj.material.isNull())
621  {
622  Ogre::MaterialManager::getSingleton().remove(obj.material->getName());
623  }
624  }
625  objects_.clear();
626 }
627 
629 {
630  if (not objects_.empty())
631  {
633  }
634 
635  for (int block = 0; block < (2 * blocks_ + 1) * (2 * blocks_ + 1); ++block)
636  {
637  // generate an unique name
638  static size_t count = 0;
639  std::string const name_suffix = std::to_string(count);
640  ++count;
641 
642  // one material per texture
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.0f, 0.0f);
648  material->setCullingMode(Ogre::CULL_NONE);
649  material->setDepthWriteEnabled(false);
650 
651  // create texture and initialize it
652  Ogre::TextureUnitState* tex_unit = material->getTechnique(0)->getPass(0)->createTextureUnitState();
653  tex_unit->setTextureFiltering(Ogre::TFO_BILINEAR);
654 
655  // create an object
656  Ogre::ManualObject* obj = scene_manager_->createManualObject("satellite_object_" + name_suffix);
657  obj->setVisible(false);
658  scene_node_->attachObject(obj);
659 
660  assert(!material.isNull());
661  objects_.emplace_back(obj, material);
662  }
663 }
664 
665 void AerialMapDisplay::update(float, float)
666 {
667  if (!ref_fix_ or !center_tile_)
668  {
669  return;
670  }
671 
672  // update tiles, if necessary
673  assembleScene();
674  // transform scene object into fixed frame
676 }
677 
678 void AerialMapDisplay::navFixCallback(sensor_msgs::NavSatFixConstPtr const& msg)
679 {
680  // reset the periodic update timer as we got an update right now
682 
683  updateCenterTile(msg);
684 
685  setStatus(StatusProperty::Ok, "Message", "NavSatFix message received");
686 }
687 
688 bool AerialMapDisplay::updateCenterTile(sensor_msgs::NavSatFixConstPtr const& msg)
689 {
690  if (!isEnabled())
691  {
692  return false;
693  }
694 
695  WGSCoordinate reference_wgs{};
696 
697  // find the WGS lat/lon of the XY reference point
698  switch (xy_reference_type_)
699  {
701  reference_wgs = { msg->latitude, msg->longitude };
702  break;
703  }
705  try
706  {
707  auto const tf_reference_utm = tf_buffer_->lookupTransform(utm_frame_, xy_reference_frame_, ros::Time(0));
708  setStatus(::rviz::StatusProperty::Ok, "XY Reference Transform", "Transform OK.");
709 
710  try
711  {
712  // If UTM zone is set to be autodetected and detection has not yet been performed, do it now
713  if (utm_zone_ < GeographicLib::UTMUPS::MINZONE)
714  {
715  int zone;
716  bool northp;
717  double e, n;
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());
722  }
723 
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);
727  setStatus(::rviz::StatusProperty::Ok, "XY reference UTM conversion", "UTM conversion OK.");
728  }
729  catch (GeographicLib::GeographicErr& err)
730  {
731  setStatus(::rviz::StatusProperty::Error, "XY reference UTM conversion", QString::fromStdString(err.what()));
732  ROS_ERROR_THROTTLE(2.0, "%s", err.what());
733  return false;
734  }
735  }
736  catch (tf2::TransformException const& ex)
737  {
738  setStatus(::rviz::StatusProperty::Error, "XY Reference Transform", QString::fromStdString(ex.what()));
739  ROS_ERROR_THROTTLE(2.0, "%s", ex.what());
740  return false;
741  }
742  break;
743  }
744  }
745 
746  // check if update is necessary
747  TileCoordinate const tile_coordinates = fromWGSCoordinate<int>(reference_wgs, zoom_);
748  TileId const new_center_tile_id{ tile_url_, tile_coordinates, zoom_ };
749  bool const center_tile_changed = (!center_tile_ || !(new_center_tile_id == *center_tile_));
750 
751  if (not center_tile_changed)
752  {
753  // TODO: Maybe we should update the transform here even if the center tile did not change?
754  // The localization might have been updated.
755  return false;
756  }
757 
758  ROS_DEBUG_NAMED("rviz_satellite", "Updating center tile to (%i, %i)", tile_coordinates.x, tile_coordinates.y);
759 
760  center_tile_ = new_center_tile_id;
761  ref_coords_ = reference_wgs;
762  ref_fix_ = msg;
763 
766  return true;
767 }
768 
770 {
771  if (!isEnabled())
772  {
773  return;
774  }
775 
776  if (tile_url_.empty())
777  {
778  setStatus(StatusProperty::Error, "TileRequest", "Tile URL is not set");
779  return;
780  }
781 
782  if (not center_tile_)
783  {
784  setStatus(StatusProperty::Error, "Message", "No NavSatFix received yet");
785  return;
786  }
787 
788  try
789  {
790  ROS_DEBUG_NAMED("rviz_satellite", "Requesting new tile images from the server");
793  }
794  catch (std::exception const& e)
795  {
796  setStatus(StatusProperty::Error, "TileRequest", QString(e.what()));
797  return;
798  }
799 }
800 
802 {
803  // the following error rate thresholds are randomly chosen
804  float const error_rate = tile_cache_.getTileServerErrorRate(tile_url_);
805  if (error_rate > 0.95)
806  {
807  setStatus(StatusProperty::Level::Error, "TileRequest", "Few or no tiles received");
808  }
809  else if (error_rate > 0.3)
810  {
811  setStatus(StatusProperty::Level::Warn, "TileRequest",
812  "Not all requested tiles have been received. Possibly the server is throttling?");
813  }
814  else
815  {
816  setStatus(StatusProperty::Level::Ok, "TileRequest", "OK");
817  }
818 }
819 
821 {
822  ROS_DEBUG_NAMED("rviz_satellite", "Starting to repaint all tiles");
823  dirty_ = true;
824 }
825 
827 {
828  // TODO: split this function into pieces, and only call the pieces when needed
829  // E.g. into: grid geometry, tile geometry, material/texture (only this is asynchronous and depends on the incoming
830  // tiles from the cache/server)
831 
832  if (!isEnabled() || !dirty_ || !center_tile_)
833  {
834  return;
835  }
836 
837  if (objects_.empty())
838  {
839  ROS_ERROR_THROTTLE_NAMED(5, "rviz_satellite", "No objects to draw on, call createTileObjects() first!");
840  return;
841  }
842 
843  dirty_ = false;
844 
845  Area area(*center_tile_, blocks_);
846 
848 
849  bool all_tiles_loaded = true;
850 
851  auto it = objects_.begin();
852  for (int xx = area.left_top.x; xx <= area.right_bottom.x; ++xx)
853  {
854  for (int yy = area.left_top.y; yy <= area.right_bottom.y; ++yy)
855  {
856  auto obj = it->object;
857  auto& material = it->material;
858  assert(!material.isNull());
859  ++it;
860 
861  TileId const to_find{ center_tile_->tile_server, { xx, yy }, center_tile_->zoom };
862 
863  OgreTile const* tile = tile_cache_.ready(to_find);
864  if (!tile)
865  {
866  // don't show tiles with old textures
867  obj->setVisible(false);
868  all_tiles_loaded = false;
869  continue;
870  }
871 
872  obj->setVisible(true);
873 
874  // update texture
875  Ogre::TextureUnitState* tex_unit = material->getTechnique(0)->getPass(0)->getTextureUnitState(0);
876  tex_unit->setTextureName(tile->texture->getName());
877 
878  // configure depth & alpha properties
879  if (alpha_ >= 0.9998)
880  {
881  material->setDepthWriteEnabled(!draw_under_);
882  material->setSceneBlending(Ogre::SBT_REPLACE);
883  }
884  else
885  {
886  material->setSceneBlending(Ogre::SBT_TRANSPARENT_ALPHA);
887  material->setDepthWriteEnabled(false);
888  }
889 
890  if (draw_under_)
891  {
892  // render under everything else
893  obj->setRenderQueueGroup(Ogre::RENDER_QUEUE_3);
894  }
895  else
896  {
897  obj->setRenderQueueGroup(Ogre::RENDER_QUEUE_MAIN);
898  }
899 
900  tex_unit->setAlphaOperation(Ogre::LBX_SOURCE1, Ogre::LBS_MANUAL, Ogre::LBS_CURRENT, alpha_);
901 
902  // tile width/ height in meter
903  double const tile_w_h_m = getTileWH(ref_coords_->lat, zoom_);
904 
905  // Note: In the following we will do two things:
906  //
907  // * We flip the position's y coordinate.
908  // * We flip the texture's v coordinate.
909  //
910  // For more explanation see the function transformAerialMap()
911 
912  // The center tile has the coordinates left-bot = (0,0) and right-top = (1,1) in the AerialMap frame.
913  double const x = (xx - center_tile_->coord.x) * tile_w_h_m;
914  // flip the y coordinate because we need to flip the tiles to align the tile's frame with the ENU "map" frame
915  double const y = -(yy - center_tile_->coord.y) * tile_w_h_m;
916 
917  // create a quad for this tile
918  // note: We have to recreate the vertices and cannot reuse the old vertices: tile_w_h_m depends on the latitude
919  obj->clear();
920 
921  obj->begin(material->getName(), Ogre::RenderOperation::OT_TRIANGLE_LIST);
922 
923  // We assign the Ogre texture coordinates in a way so that we flip the
924  // texture along the v coordinate. For example, we assign the bottom left
925  //
926  // Note that the Ogre texture coordinate system is: (0,0) = top left of the loaded image and (1,1) = bottom right
927  // of the loaded image
928 
929  // bottom left
930  obj->position(x, y, 0.0f);
931  obj->textureCoord(0.0f, 0.0f);
932  obj->normal(0.0f, 0.0f, 1.0f);
933 
934  // top right
935  obj->position(x + tile_w_h_m, y + tile_w_h_m, 0.0f);
936  obj->textureCoord(1.0f, 1.0f);
937  obj->normal(0.0f, 0.0f, 1.0f);
938 
939  // top left
940  obj->position(x, y + tile_w_h_m, 0.0f);
941  obj->textureCoord(0.0f, 1.0f);
942  obj->normal(0.0f, 0.0f, 1.0f);
943 
944  // bottom left
945  obj->position(x, y, 0.0f);
946  obj->textureCoord(0.0f, 0.0f);
947  obj->normal(0.0f, 0.0f, 1.0f);
948 
949  // bottom right
950  obj->position(x + tile_w_h_m, y, 0.0f);
951  obj->textureCoord(1.0f, 0.0f);
952  obj->normal(0.0f, 0.0f, 1.0f);
953 
954  // top right
955  obj->position(x + tile_w_h_m, y + tile_w_h_m, 0.0f);
956  obj->textureCoord(1.0f, 1.0f);
957  obj->normal(0.0f, 0.0f, 1.0f);
958 
959  obj->end();
960  }
961  }
962 
963  // since not all tiles were loaded yet, this function has to be called again
964  if (!all_tiles_loaded)
965  {
966  dirty_ = true;
967  }
968  else
969  {
970  ROS_DEBUG_NAMED("rviz_satellite", "Finished assembling all tiles");
971  }
972 
974 
976 }
977 
979 {
980  switch (map_transform_type_)
981  {
984  break;
987  break;
988  }
989 }
990 
992 {
993  if (!ref_fix_ or !center_tile_)
994  {
995  ROS_FATAL_THROTTLE_NAMED(2, "rviz_satellite", "ref_fix_ not set, can't create transforms");
996  return;
997  }
998 
999  // We will use three frames in this function:
1000  //
1001  // * The frame from the NavSatFix message. It is rigidly attached to the robot.
1002  // * The ENU world frame "map_frame_".
1003  // * The frame of the tiles. We assume that the tiles are in a frame where x points eastwards and y southwards (ENU).
1004  // This
1005  // frame is used by OSM and Google Maps, see https://en.wikipedia.org/wiki/Web_Mercator_projection and
1006  // https://developers.google.com/maps/documentation/javascript/coordinates.
1007 
1008  // translation of NavSatFix frame w.r.t. the map frame
1009  // NOTE: due to ENU convention, orientation is not needed, the tiles are rigidly attached to ENU
1010  tf2::Vector3 t_navsat_map;
1011 
1012  try
1013  {
1014  // Use a real TfBuffer for looking up this transform. The FrameManager only supplies transform to/from the
1015  // currently selected RViz fixed-frame, which is of no help here.
1016  auto const tf_navsat_map =
1017  tf_buffer_->lookupTransform(map_frame_, ref_fix_->header.frame_id, ref_fix_->header.stamp);
1018  tf2::fromMsg(tf_navsat_map.transform.translation, t_navsat_map);
1019  }
1020  catch (tf2::TransformException const& ex)
1021  {
1022  // retry the lookup after a while; we do not use the timeout parameter of lookupTransform() as that timeout is in
1023  // ROS time and the waiting can freeze when ROS time is paused; this freeze would then freeze the whole Rviz UI
1024  try
1025  {
1026  ros::WallDuration(0.01).sleep();
1027  auto const tf_navsat_map =
1028  tf_buffer_->lookupTransform(map_frame_, ref_fix_->header.frame_id, ref_fix_->header.stamp);
1029  tf2::fromMsg(tf_navsat_map.transform.translation, t_navsat_map);
1030  }
1031  catch (tf2::TransformException const& ex)
1032  {
1033  setStatus(StatusProperty::Error, "Transform", QString::fromStdString(ex.what()));
1034  return;
1035  }
1036  }
1037 
1038  // FIXME: note the <double> template! this is different from center_tile_.coord, otherwise we could just use that
1039  // since center_tile_ and ref_fix_ are in sync
1040  auto const ref_fix_tile_coords = fromWGSCoordinate<double>(*ref_coords_, zoom_);
1041 
1042  // In assembleScene() we shift the AerialMap so that the center tile's left-bottom corner has the coordinate (0,0).
1043  // Therefore we can calculate the NavSatFix coordinate (in the AerialMap frame) by just looking at the fractional part
1044  // of the coordinate. That is we calculate the offset from the left bottom corner of the center tile.
1045  auto const center_tile_offset_x = ref_fix_tile_coords.x - std::floor(ref_fix_tile_coords.x);
1046  // In assembleScene() the tiles are created so that the texture is flipped along the y coordinate. Since we want to
1047  // calculate the positions of the center tile, we also need to flip the texture's v coordinate here.
1048  auto const center_tile_offset_y = 1 - (ref_fix_tile_coords.y - std::floor(ref_fix_tile_coords.y));
1049 
1050  double const tile_w_h_m = getTileWH(ref_coords_->lat, zoom_);
1051  ROS_DEBUG_NAMED("rviz_satellite", "Tile resolution is %.1fm", tile_w_h_m);
1052 
1053  // translation of the center-tile w.r.t. the NavSatFix frame
1054  tf2::Vector3 t_centertile_navsat = { center_tile_offset_x * tile_w_h_m, center_tile_offset_y * tile_w_h_m, 0 };
1055 
1056  center_tile_pose_.header.frame_id = map_frame_;
1057  center_tile_pose_.header.stamp = ref_fix_->header.stamp;
1058  tf2::toMsg(t_navsat_map - t_centertile_navsat, center_tile_pose_.pose.position);
1059 }
1060 
1062 {
1063  if (!ref_fix_ or !center_tile_)
1064  {
1065  ROS_FATAL_THROTTLE_NAMED(2, "rviz_satellite", "ref_fix_ not set, can't create transforms");
1066  return;
1067  }
1068 
1069  // tile ID (integer x/y/zoom) corresponding to the downloaded tile / navsat message
1070  auto const tile = fromWGSCoordinate<int>(*ref_coords_, zoom_);
1071 
1072  // Latitude and longitude of this tile's origin
1073  auto const tileWGS = toWGSCoordinate<int>(tile, zoom_);
1074 
1075  // Tile's origin in UTM coordinates
1076  double northing, easting;
1077  int utm_zone;
1078  bool northp;
1079 
1080  try
1081  {
1082  GeographicLib::UTMUPS::Forward(tileWGS.lat, tileWGS.lon, utm_zone, northp, easting, northing, utm_zone_);
1083  }
1084  catch (GeographicLib::GeographicErr& err)
1085  {
1086  ROS_ERROR_THROTTLE(2.0, "Error transforming lat-lon to UTM: %s", err.what());
1087  if (utm_zone_ != GeographicLib::UTMUPS::STANDARD)
1088  {
1089  try
1090  {
1091  GeographicLib::UTMUPS::Forward(tileWGS.lat, tileWGS.lon, utm_zone, northp, easting, northing,
1092  GeographicLib::UTMUPS::STANDARD);
1093  ROS_INFO_THROTTLE(2.0, "Trying to autodetect UTM zone instead of using zone %i", utm_zone_);
1094  }
1095  catch (GeographicLib::GeographicErr& err)
1096  {
1097  setStatus(::rviz::StatusProperty::Error, "UTM", QString::fromStdString(err.what()));
1098  return;
1099  }
1100  }
1101  else
1102  {
1103  setStatus(::rviz::StatusProperty::Error, "UTM", QString::fromStdString(err.what()));
1104  return;
1105  }
1106  }
1107 
1108  setStatus(::rviz::StatusProperty::Ok, "UTM", "Conversion from lat/lon to UTM is OK.");
1109 
1110  if (utm_zone != utm_zone_)
1111  {
1112  ROS_INFO("UTM zone has been updated to %s.", GeographicLib::UTMUPS::EncodeZone(utm_zone, northp).c_str());
1113  utm_zone_property_->setInt(utm_zone);
1114  }
1115 
1116  center_tile_pose_.header.stamp = ref_fix_->header.stamp;
1117  center_tile_pose_.header.frame_id = utm_frame_;
1118  center_tile_pose_.pose.position.x = easting;
1119  center_tile_pose_.pose.position.y = northing;
1120 
1121  switch (z_reference_type_)
1122  {
1124  center_tile_pose_.pose.position.z = ref_fix_->altitude;
1125  break;
1128  {
1129  center_tile_pose_.pose.position.z = 0;
1130  setStatus(StatusProperty::Ok, "Z Reference Transform", "Transform OK.");
1131  }
1132  else
1133  {
1134  try
1135  {
1136  auto const tf_reference_utm =
1137  tf_buffer_->lookupTransform(utm_frame_, z_reference_frame_, ros::Time(0));
1138  center_tile_pose_.pose.position.z = tf_reference_utm.transform.translation.z;
1139  setStatus(StatusProperty::Ok, "Z Reference Transform", "Transform OK.");
1140  }
1141  catch (tf2::TransformException const& ex)
1142  {
1143  setStatus(StatusProperty::Error, "Z Reference Transform", QString::fromStdString(ex.what()));
1144  }
1145  }
1146  break;
1147  }
1148 }
1149 
1151 {
1153  {
1154  return;
1155  }
1156 
1157  if (!ref_fix_ || !center_tile_)
1158  {
1159  return;
1160  }
1161 
1162  try
1163  {
1164  auto const tf_reference_utm =
1165  tf_buffer_->lookupTransform(utm_frame_, xy_reference_frame_, ros::Time(0));
1166  setStatus(::rviz::StatusProperty::Ok, "XY Reference Transform", "Transform OK.");
1167 
1168  try
1169  {
1170  WGSCoordinate reference_wgs{};
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);
1174  setStatus(::rviz::StatusProperty::Ok, "XY reference UTM conversion", "UTM conversion OK.");
1175 
1176  auto new_fix = boost::make_shared<sensor_msgs::NavSatFix>();
1177  *new_fix = *ref_fix_;
1178  new_fix->header.stamp = ros::Time::now();
1179  new_fix->latitude = reference_wgs.lat;
1180  new_fix->longitude = reference_wgs.lon;
1181  new_fix->altitude = utm_coords.z;
1182 
1183  // update the center tile; if it stays the same, at least update the transforms so that z reference is updated
1184  if (!updateCenterTile(new_fix))
1185  {
1187  }
1188 
1189  setStatus(StatusProperty::Ok, "Message", "Position reference updated.");
1190  }
1191  catch (GeographicLib::GeographicErr& err)
1192  {
1193  setStatus(::rviz::StatusProperty::Error, "XY reference UTM conversion", QString::fromStdString(err.what()));
1194  ROS_ERROR_THROTTLE(2.0, "%s", err.what());
1195  return;
1196  }
1197  }
1198  catch (tf2::TransformException const& ex)
1199  {
1200  setStatus(::rviz::StatusProperty::Error, "XY Reference Transform", QString::fromStdString(ex.what()));
1201  ROS_ERROR_THROTTLE(2.0, "%s", ex.what());
1202  return;
1203  }
1204 }
1205 
1207 {
1208  // orientation of the tile w.r.t. the fixed-frame
1209  Ogre::Quaternion o_centertile_fixed;
1210  // translation of the tile w.r.t. the fixed-frame
1211  Ogre::Vector3 t_centertile_fixed;
1212 
1213  auto header = center_tile_pose_.header;
1214  header.stamp = ros::Time(); // ros::Time::now() would be wrong, see the discussion in #105
1215  const auto& frame_name = header.frame_id;
1216 
1217  auto tile_pose = center_tile_pose_.pose;
1218  if (z_offset_ != 0.0)
1219  {
1220  tile_pose.position.z += z_offset_;
1221  }
1222 
1223  // transform the tile origin to fixed frame
1224  if (context_->getFrameManager()->transform(header, tile_pose, t_centertile_fixed, o_centertile_fixed))
1225  {
1226  setStatus(::rviz::StatusProperty::Ok, "Transform", "Transform OK");
1227 
1228  scene_node_->setPosition(t_centertile_fixed);
1229  scene_node_->setOrientation(o_centertile_fixed);
1230  }
1231  else
1232  {
1233  // display error
1234  std::string error;
1235  if (context_->getFrameManager()->transformHasProblems(frame_name, ros::Time(), error))
1236  {
1237  setStatus(::rviz::StatusProperty::Error, "Transform", QString::fromStdString(error));
1238  }
1239  else
1240  {
1241  setStatus(::rviz::StatusProperty::Error, "Transform",
1242  QString::fromStdString("Could not transform from [" + frame_name + "] to Fixed Frame [" +
1243  fixed_frame_.toStdString() + "] for an unknown reason"));
1244  }
1245  }
1246 }
1247 
1249 {
1250  Display::reset();
1251  // unsubscribe, clear, resubscribe
1252  updateTopic();
1253 }
1254 
1255 } // namespace rviz
1256 
void request(Area const &area)
void setMin(float min)
PositionReferenceType getPositionReferenceType() const
bool updateCenterTile(sensor_msgs::NavSatFixConstPtr const &msg)
IntProperty * utm_zone_property_
std::string getFrameStd() const
void setMax(float max)
std::string map_frame_
the map frame, rigidly attached to the world with ENU convention - see https://www.ros.org/reps/rep-0105.html#map
bool transformHasProblems(const std::string &frame, ros::Time time, std::string &error)
EnumProperty * map_transform_type_property_
boost::optional< TileId > center_tile_
Last request()ed tile id (which is the center tile)
f
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
DisplayContext * context_
float alpha_
the alpha value of the tile&#39;s material
ros::NodeHandle update_nh_
FloatProperty * z_offset_property_
void setPeriod(const Duration &period, bool reset=true)
void update(float, float) override
void setMin(int min)
static constexpr int MAX_BLOCKS
Max number of adjacent blocks to support.
Definition: mercator.h:20
std::string tile_url_
the URL of the tile server to use
Displays a satellite map along the XY plane.
IntProperty * blocks_property_
std::string getTopicStd() const
void setInt(int new_value)
PositionReferenceProperty * xy_reference_property_
FloatProperty * alpha_property_
TileCacheDelay< OgreTile > tile_cache_
caches tile images, hashed by their fetch URL
double getTileWH(double const latitude, int const zoom)
Definition: mercator.h:50
static constexpr int MAX_ZOOM
Max zoom level to support.
Definition: mercator.h:23
std::string utm_frame_
the utm frame, representing a UTM coordinate frame in a chosen zone
Ogre::SceneNode * scene_node_
std::string getStdString()
void setMax(int max)
TfFrameProperty * utm_frame_property_
TfFrameProperty * map_frame_property_
QString fixed_frame_
MapTransformType
Whether the tiles should be transformed via an intermediate map frame, or directly via a UTM frame...
#define ROS_DEBUG_NAMED(name,...)
ros::Duration tf_reference_update_duration_
timeout for periodic TF_FRAME reference update
geometry_msgs::PoseStamped center_tile_pose_
translation of the center-tile w.r.t. the map/utm frame
#define ROS_INFO_THROTTLE(period,...)
virtual void addOption(const QString &option, int value=0)
PositionReferenceType xy_reference_type_
Type of XY position reference.
#define ROS_ERROR_THROTTLE_NAMED(period, name,...)
ros::Timer tf_reference_update_timer_
timer that updates the reference position when using TF_FRAME references
#define ROS_WARN_THROTTLE(period,...)
virtual void reset()
#define ROS_INFO(...)
MapTransformType map_transform_type_
Whether the tiles should be transformed via an intermediate map frame, or directly via a UTM frame...
RosTopicProperty * topic_property_
#define ROS_ERROR_THROTTLE(period,...)
Definition: area.h:31
float getTileServerErrorRate(std::string const &tile_server) const
Calculate the error rate of a tile server.
Definition: tile_cache.h:148
sensor_msgs::NavSatFixConstPtr ref_fix_
the last NavSatFix message that lead to updating the tiles
void fromMsg(const A &, B &b)
bool dirty_
whether we need to re-query and re-assemble the tiles
std::string z_reference_frame_
Z position reference TF frame (if TF_FRAME type is used)
Tile const * ready(TileId const &to_find) const
int blocks_
the number of tiles loaded in each direction around the center tile
bool transform(const Header &header, const geometry_msgs::Pose &pose, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
virtual FrameManager * getFrameManager() const=0
double z_offset_
Offset of the tiles in Z axis (relative to map/utm)
Property(const QString &name=QString(), const QVariant default_value=QVariant(), const QString &description=QString(), Property *parent=nullptr, const char *changed_slot=nullptr, QObject *receiver=nullptr)
bool sleep() const
std::string xy_reference_frame_
XY position reference TF frame (if TF_FRAME type is used)
std::unordered_map< MapTransformType, QString > mapTransformTypeStrings
void setShouldBeSaved(bool save)
boost::optional< WGSCoordinate > ref_coords_
lat/lon of the reference position that lead to updating the tiles
TileCoordinate right_bottom
Definition: area.h:34
Ogre::SceneManager * scene_manager_
#define ROS_FATAL_THROTTLE_NAMED(period, name,...)
std::shared_ptr< tf2_ros::Buffer const > tf_buffer_
buffer for tf lookups not related to fixed-frame
bool draw_under_
determines which render queue to use
virtual int getInt() const
B toMsg(const A &a)
bool isEnabled() const
bool setValue(const QVariant &new_value) override
ros::NodeHandle threaded_nh_
PositionReferenceType z_reference_type_
Type of Z position reference.
virtual float getFloat() const
StringProperty * tile_url_property_
ros::Subscriber navsat_fix_sub_
the subscriber for the NavSatFix topic
void setFrameManager(FrameManager *frame_manager)
void tfReferencePeriodicUpdate(const ros::TimerEvent &)
int zoom_
the zoom to use (Mercator)
static Time now()
TileCoordinate left_top
Definition: area.h:33
QString getTopic() const
virtual void deleteStatus(const QString &name)
const std::string header
Ogre::TexturePtr texture
Definition: ogre_tile.h:27
virtual QVariant getValue() const
PositionReferenceProperty * z_reference_property_
void navFixCallback(sensor_msgs::NavSatFixConstPtr const &msg)
std::vector< MapObject > objects_
the tile scene objects
virtual int getOptionInt()
Definition: tile_id.h:31
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
#define ROS_ERROR(...)
int utm_zone_
UTM zone to work in.
void purge(Area const &area)
Definition: tile_cache.h:128
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
const std::shared_ptr< tf2_ros::Buffer > getTF2BufferPtr()


rviz_satellite
Author(s): Gareth Cross , Andre Schröder
autogenerated on Thu May 4 2023 02:31:43