aerialmap_display.h
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 #pragma once
16 
17 #include <string>
18 #include <vector>
19 
20 #include <boost/optional.hpp>
21 
22 #include <geometry_msgs/PoseStamped.h>
23 #include <ros/ros.h>
24 #include <ros/time.h>
25 #include <rviz/display.h>
26 #include <sensor_msgs/NavSatFix.h>
27 #include <tf2_ros/buffer.h>
28 
29 #include <OGRE/OgreMaterial.h>
30 #include <OGRE/OgreVector3.h>
31 
32 #include "coordinates.h"
33 #include "ogre_tile.h"
34 #include "position_reference.h"
35 #include "tile_cache_delay.h"
36 
37 namespace Ogre
38 {
39 class ManualObject;
40 }
41 
42 namespace rviz
43 {
44 class EnumProperty;
45 class FloatProperty;
46 class IntProperty;
47 class PositionReferenceProperty;
48 class Property;
49 class RosTopicProperty;
50 class StringProperty;
51 class TfFrameProperty;
52 
57 enum class MapTransformType
58 {
61 };
62 
66 class AerialMapDisplay : public Display
67 {
68  Q_OBJECT
69 public:
71  ~AerialMapDisplay() override;
72 
73  // Overrides from Display
74  void reset() override;
75  void update(float, float) override;
76 
77 protected Q_SLOTS:
78  void updateAlpha();
79  void updateTopic();
80  void updateDrawUnder();
81  void updateTileUrl();
82  void updateZoom();
83  void updateBlocks();
84  void updateMapTransformType();
85  void updateMapFrame();
86  void updateUtmFrame();
87  void updateUtmZone();
88  void updateXYReference();
89  void updateZReference();
90  void updateZOffset();
91 
92 protected:
93  // overrides from Display
94  void onEnable() override;
95  void onDisable() override;
96  void onInitialize() override;
97 
98  virtual void subscribe();
99  virtual void unsubscribe();
100 
104  void navFixCallback(sensor_msgs::NavSatFixConstPtr const& msg);
105 
109  void requestTileTextures();
110 
115  bool updateCenterTile(sensor_msgs::NavSatFixConstPtr const& msg);
116 
120  void assembleScene();
121 
125  void triggerSceneAssembly();
126 
130  void clearAll();
131 
135  void destroyTileObjects();
136 
140  void createTileObjects();
141 
145  void transformTileToReferenceFrame();
146 
150  void transformTileToUtmFrame();
151 
155  void transformTileToMapFrame();
156 
160  void transformMapTileToFixedFrame();
161 
165  void checkRequestErrorRate();
166 
170  void tfReferencePeriodicUpdate(const ros::TimerEvent&);
171 
175  struct MapObject
176  {
177  Ogre::ManualObject* object;
178  Ogre::MaterialPtr material;
179 
180  MapObject(Ogre::ManualObject* o, Ogre::MaterialPtr m) : object(o), material(m)
181  {
182  assert(!material.isNull());
183  }
184  };
185 
187  std::vector<MapObject> objects_;
188 
191 
192  // properties
206 
208  float alpha_;
212  std::string tile_url_;
214  int zoom_;
216  int blocks_;
220  std::string map_frame_;
222  std::string utm_frame_;
228  std::string xy_reference_frame_;
232  std::string z_reference_frame_;
234  double z_offset_;
235 
236  // tile management
238  bool dirty_{ false };
240  sensor_msgs::NavSatFixConstPtr ref_fix_{ nullptr };
242  boost::optional<WGSCoordinate> ref_coords_;
246  boost::optional<TileId> center_tile_{ boost::none };
248  geometry_msgs::PoseStamped center_tile_pose_;
249 
251  std::shared_ptr<tf2_ros::Buffer const> tf_buffer_{ nullptr };
252 
257 };
258 
259 } // namespace rviz
IntProperty * utm_zone_property_
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
EnumProperty * map_transform_type_property_
float alpha_
the alpha value of the tile&#39;s material
FloatProperty * z_offset_property_
std::string tile_url_
the URL of the tile server to use
Displays a satellite map along the XY plane.
IntProperty * blocks_property_
PositionReferenceProperty * xy_reference_property_
FloatProperty * alpha_property_
TileCacheDelay< OgreTile > tile_cache_
caches tile images, hashed by their fetch URL
std::string utm_frame_
the utm frame, representing a UTM coordinate frame in a chosen zone
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
TfFrameProperty * utm_frame_property_
PositionReferenceType
Which reference should be used for determining position.
TfFrameProperty * map_frame_property_
MapTransformType
Whether the tiles should be transformed via an intermediate map frame, or directly via a UTM frame...
void subscribe()
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
PositionReferenceType xy_reference_type_
Type of XY position reference.
ros::Timer tf_reference_update_timer_
timer that updates the reference position when using TF_FRAME references
MapTransformType map_transform_type_
Whether the tiles should be transformed via an intermediate map frame, or directly via a UTM frame...
RosTopicProperty * topic_property_
std::string z_reference_frame_
Z position reference TF frame (if TF_FRAME type is used)
int blocks_
the number of tiles loaded in each direction around the center tile
double z_offset_
Offset of the tiles in Z axis (relative to map/utm)
std::string xy_reference_frame_
XY position reference TF frame (if TF_FRAME type is used)
boost::optional< WGSCoordinate > ref_coords_
lat/lon of the reference position that lead to updating the tiles
bool draw_under_
determines which render queue to use
PositionReferenceType z_reference_type_
Type of Z position reference.
StringProperty * tile_url_property_
ros::Subscriber navsat_fix_sub_
the subscriber for the NavSatFix topic
MapObject(Ogre::ManualObject *o, Ogre::MaterialPtr m)
int zoom_
the zoom to use (Mercator)
PositionReferenceProperty * z_reference_property_
std::vector< MapObject > objects_
the tile scene objects
void unsubscribe()
int utm_zone_
UTM zone to work in.


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