Go to the documentation of this file.
30 #ifndef RVIZ_MAP_DISPLAY_H
31 #define RVIZ_MAP_DISPLAY_H
34 #include <boost/thread/thread.hpp>
36 #include <OgreTexture.h>
37 #include <OgreMaterial.h>
39 #include <OgreSharedPtr.h>
42 #include <nav_msgs/MapMetaData.h>
45 #include <nav_msgs/OccupancyGrid.h>
46 #include <map_msgs/OccupancyGridUpdate.h>
61 class QuaternionProperty;
62 class RosTopicProperty;
108 void reset()
override;
123 void setTopic(
const QString& topic,
const QString& datatype)
override;
140 void update(
float wall_dt,
float ros_dt)
override;
143 void incomingMap(
const nav_msgs::OccupancyGrid::ConstPtr& msg);
std::vector< Swatch * > swatches
RosTopicProperty * topic_property_
Ogre::ManualObject * manual_object_
IntProperty * height_property_
EnumProperty * color_scheme_property_
Property specialized to provide getter for booleans.
Swatch(MapDisplay *parent, unsigned int x, unsigned int y, unsigned int width, unsigned int height, float resolution)
BoolProperty * transform_timestamp_property_
FloatProperty * resolution_property_
QuaternionProperty * orientation_property_
ros::Subscriber update_sub_
std::vector< bool > color_scheme_transparency_
FloatProperty * alpha_property_
Property specialized to enforce floating point max/min.
A single element of a property tree, with a name, value, description, and possibly children.
void onDisable() override
Derived classes override this to do the actual work of disabling themselves.
void updateAlpha(const Ogre::SceneBlendType sceneBlending, bool depthWrite, AlphaSetter *alpha_setter)
Ogre::SceneNode * scene_node_
Ogre::TexturePtr texture_
nav_msgs::OccupancyGrid current_map_
void fixedFrameChanged() override
Called by setFixedFrame(). Override to respond to changes to fixed_frame_.
void incomingMap(const nav_msgs::OccupancyGrid::ConstPtr &msg)
Copy msg into current_map_ and set flag map_updated_.
Ogre::MaterialPtr material_
void update(float wall_dt, float ros_dt) override
Called periodically by the visualization manager.
virtual void unsubscribe()
BoolProperty * unreliable_property_
Property * draw_under_property_
std::vector< Ogre::TexturePtr > palette_textures_
IntProperty * width_property_
void incomingUpdate(const map_msgs::OccupancyGridUpdate::ConstPtr &update)
Copy update's data into current_map_ and set flag map_updated_.
void onEnable() override
Derived classes override this to do the actual work of enabling themselves.
Displays a map along the XY plane.
void setTopic(const QString &topic, const QString &datatype) override
Set the ROS topic to listen to for this display.
VectorProperty * position_property_
void onInitialize() override
Override this function to do subclass-specific initialization.
void reset() override
Called to tell the display to clear its state.
Property specialized to provide max/min enforcement for integers.
rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Fri Aug 2 2024 08:43:09