Class AerialMapDisplay
Defined in File aerialmap_display.hpp
Inheritance Relationships
Base Type
public rviz_common::RosTopicDisplay< sensor_msgs::msg::NavSatFix >
Class Documentation
-
class AerialMapDisplay : public rviz_common::RosTopicDisplay<sensor_msgs::msg::NavSatFix>
Display a satellite map on the XY plane.
Public Functions
-
AerialMapDisplay()
-
~AerialMapDisplay() override
-
void onInitialize() override
-
void reset() override
-
void update(float, float) override
Protected Functions
-
void onEnable() override
-
void onDisable() override
-
bool validateProperties()
-
void shiftMap(TileCoordinate center_tile, Ogre::Vector2i offset, double size)
-
void buildMap(TileCoordinate center_tile, double size)
-
void buildTile(TileCoordinate coordinate, Ogre::Vector2i offset, double size)
-
void resetMap()
-
void resetTileServerError()
-
void updateAlpha(const rclcpp::Time &t)
-
rclcpp::Duration tf_tolerance() const
-
TileCoordinate centerTile() const
Protected Attributes
-
rviz_common::properties::StringProperty *tile_url_property_ = nullptr
-
rviz_common::properties::IntProperty *zoom_property_ = nullptr
-
rviz_common::properties::IntProperty *blocks_property_ = nullptr
-
rviz_common::properties::FloatProperty *alpha_property_ = nullptr
-
rviz_common::properties::FloatProperty *timeout_property_ = nullptr
-
rviz_common::properties::FloatProperty *tf_tolerance_property_ = nullptr
-
rviz_common::properties::Property *draw_under_property_ = nullptr
-
rviz_common::properties::Property *local_map_property_ = nullptr
-
rviz_common::properties::FloatProperty *local_meter_per_pixel_z0_property_ = nullptr
-
rviz_common::properties::StringProperty *local_origin_crs_property_ = nullptr
-
rviz_common::properties::FloatProperty *local_origin_x_property_ = nullptr
-
rviz_common::properties::FloatProperty *local_origin_y_property_ = nullptr
-
std::mutex tiles_mutex_
-
TileClient tile_client_
-
TileMapInformation tile_map_info_
-
std::map<TileId, TileObject> tiles_
-
sensor_msgs::msg::NavSatFix::ConstSharedPtr last_fix_
-
bool tile_server_had_errors_ = {false}
Protected Slots
-
void updateAlpha()
-
void updateDrawUnder()
-
void updateTileUrl()
-
void updateZoom()
-
void updateBlocks()
-
void updateLocalMap()
-
void updateLocalTileMapInformation()
Protected Static Attributes
-
static const std::string MAP_FRAME
-
static const QString MESSAGE_STATUS
-
static const QString TILE_REQUEST_STATUS
-
static const QString PROPERTIES_STATUS
-
static const QString ORIENTATION_STATUS
-
static const QString TRANSFORM_STATUS
-
static const QString PROJ_TRANSFORM_STATUS
-
AerialMapDisplay()