Go to the documentation of this file.
20 #include <boost/optional.hpp>
22 #include <geometry_msgs/PoseStamped.h>
26 #include <sensor_msgs/NavSatFix.h>
29 #include <OGRE/OgreMaterial.h>
30 #include <OGRE/OgreVector3.h>
47 class PositionReferenceProperty;
49 class RosTopicProperty;
51 class TfFrameProperty;
74 void reset()
override;
75 void update(
float,
float)
override;
240 sensor_msgs::NavSatFixConstPtr
ref_fix_{
nullptr };
251 std::shared_ptr<tf2_ros::Buffer const>
tf_buffer_{
nullptr };
PositionReferenceType z_reference_type_
Type of Z position reference.
ros::Timer tf_reference_update_timer_
timer that updates the reference position when using TF_FRAME references
sensor_msgs::NavSatFixConstPtr ref_fix_
the last NavSatFix message that lead to updating the tiles
std::string map_frame_
the map frame, rigidly attached to the world with ENU convention - see https://www....
std::string tile_url_
the URL of the tile server to use
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
ros::Duration tf_reference_update_duration_
timeout for periodic TF_FRAME reference update
void transformMapTileToFixedFrame()
IntProperty * utm_zone_property_
int zoom_
the zoom to use (Mercator)
MapTransformType
Whether the tiles should be transformed via an intermediate map frame, or directly via a UTM frame.
std::string xy_reference_frame_
XY position reference TF frame (if TF_FRAME type is used)
float alpha_
the alpha value of the tile's material
std::vector< MapObject > objects_
the tile scene objects
std::string utm_frame_
the utm frame, representing a UTM coordinate frame in a chosen zone
Ogre::ManualObject * object
geometry_msgs::PoseStamped center_tile_pose_
translation of the center-tile w.r.t. the map/utm frame
Property * draw_under_property_
ros::Subscriber navsat_fix_sub_
the subscriber for the NavSatFix topic
void onInitialize() override
void transformTileToMapFrame()
int utm_zone_
UTM zone to work in.
void requestTileTextures()
~AerialMapDisplay() override
boost::optional< WGSCoordinate > ref_coords_
lat/lon of the reference position that lead to updating the tiles
void navFixCallback(sensor_msgs::NavSatFixConstPtr const &msg)
bool updateCenterTile(sensor_msgs::NavSatFixConstPtr const &msg)
EnumProperty * map_transform_type_property_
virtual void unsubscribe()
void tfReferencePeriodicUpdate(const ros::TimerEvent &)
void updateMapTransformType()
void destroyTileObjects()
Ogre::MaterialPtr material
TileCacheDelay< OgreTile > tile_cache_
caches tile images, hashed by their fetch URL
boost::optional< TileId > center_tile_
Last request()ed tile id (which is the center tile)
PositionReferenceType xy_reference_type_
Type of XY position reference.
std::string z_reference_frame_
Z position reference TF frame (if TF_FRAME type is used)
double z_offset_
Offset of the tiles in Z axis (relative to map/utm)
FloatProperty * alpha_property_
void onDisable() override
PositionReferenceProperty * xy_reference_property_
void transformTileToReferenceFrame()
PositionReferenceType
Which reference should be used for determining position.
void update(float, float) override
void checkRequestErrorRate()
StringProperty * tile_url_property_
TfFrameProperty * map_frame_property_
void triggerSceneAssembly()
FloatProperty * z_offset_property_
bool dirty_
whether we need to re-query and re-assemble the tiles
IntProperty * zoom_property_
int blocks_
the number of tiles loaded in each direction around the center tile
void transformTileToUtmFrame()
Displays a satellite map along the XY plane.
MapObject(Ogre::ManualObject *o, Ogre::MaterialPtr m)
RosTopicProperty * topic_property_
IntProperty * blocks_property_
TfFrameProperty * utm_frame_property_
PositionReferenceProperty * z_reference_property_
MapTransformType map_transform_type_
Whether the tiles should be transformed via an intermediate map frame, or directly via a UTM frame.
rviz_satellite
Author(s): Gareth Cross
, Andre Schröder
autogenerated on Thu May 4 2023 02:47:22