Class MapDisplay

Inheritance Relationships

Base Type

  • public rviz_common::MessageFilterDisplay< nav_msgs::msg::OccupancyGrid >

Class Documentation

class MapDisplay : public rviz_common::MessageFilterDisplay<nav_msgs::msg::OccupancyGrid>

Displays a map along the XY plane.

Public Functions

explicit MapDisplay(rviz_common::DisplayContext *context)
MapDisplay()
~MapDisplay() override
void onInitialize() override
void fixedFrameChanged() override
void reset() override
inline float getResolution()
inline size_t getWidth()
inline size_t getHeight()
void processMessage(nav_msgs::msg::OccupancyGrid::ConstSharedPtr msg) override

Copy msg into current_map_ and call showMap().

Public Slots

void showMap()

Signals

void mapUpdated()

Emitted when a new map is received.

Protected Functions

void updateTopic() override
void update(float wall_dt, float ros_dt) override
void subscribe() override
void unsubscribe() override
void onEnable() override
void incomingUpdate(map_msgs::msg::OccupancyGridUpdate::ConstSharedPtr update)

Copy update’s data into current_map_ and call showMap().

bool updateDataOutOfBounds(map_msgs::msg::OccupancyGridUpdate::ConstSharedPtr update) const
void updateMapDataInMemory(map_msgs::msg::OccupancyGridUpdate::ConstSharedPtr update)
void clear()
void subscribeToUpdateTopic()
void unsubscribeToUpdateTopic()
void showValidMap()
void resetSwatchesIfNecessary(size_t width, size_t height, float resolution)
void createSwatches()
void doubleSwatchNumber(size_t &swatch_width, size_t &swatch_height, int &number_swatches) const
void tryCreateSwatches(size_t width, size_t height, float resolution, size_t swatch_width, size_t swatch_height, int number_swatches)
size_t getEffectiveDimension(size_t map_dimension, size_t swatch_dimension, size_t position)
void updateSwatches() const

Protected Attributes

std::vector<std::shared_ptr<Swatch>> swatches_
std::vector<Ogre::TexturePtr> palette_textures_
std::vector<Ogre::TexturePtr> palette_textures_binary_
std::vector<bool> color_scheme_transparency_
bool loaded_
float resolution_
size_t width_
size_t height_
std::string frame_
nav_msgs::msg::OccupancyGrid current_map_
rclcpp::Subscription<map_msgs::msg::OccupancyGridUpdate>::SharedPtr update_subscription_
rclcpp::QoS update_profile_
rclcpp::Time subscription_start_time_
rviz_common::properties::RosTopicProperty *update_topic_property_
rviz_common::properties::QosProfileProperty *update_profile_property_
rviz_common::properties::FloatProperty *resolution_property_
rviz_common::properties::IntProperty *width_property_
rviz_common::properties::IntProperty *height_property_
rviz_common::properties::VectorProperty *position_property_
rviz_common::properties::QuaternionProperty *orientation_property_
rviz_common::properties::FloatProperty *alpha_property_
rviz_common::properties::Property *draw_under_property_
rviz_common::properties::EnumProperty *color_scheme_property_
rviz_common::properties::BoolProperty *transform_timestamp_property_
rviz_common::properties::BoolProperty *binary_view_property_
rviz_common::properties::IntProperty *binary_threshold_property_
uint32_t update_messages_received_

Protected Slots

void updateAlpha()
void updateDrawUnder() const
void updatePalette()
void updateBinaryThreshold()
void transformMap()

Show current_map_ in the scene.

void updateMapUpdateTopic()