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> 38 #include <OgreVector3.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;
80 void updateAlpha(
const Ogre::SceneBlendType sceneBlending,
bool depthWrite,
AlphaSetter* alpha_setter);
89 unsigned int x_,
y_, width_, height_;
106 void onInitialize()
override;
107 void fixedFrameChanged()
override;
108 void reset()
override;
123 void setTopic(
const QString& topic,
const QString&
datatype)
override;
132 void updateDrawUnder();
133 void updatePalette();
140 void onEnable()
override;
141 void onDisable()
override;
145 void update(
float wall_dt,
float ros_dt)
override;
148 void incomingMap(
const nav_msgs::OccupancyGrid::ConstPtr& msg);
151 void incomingUpdate(
const map_msgs::OccupancyGridUpdate::ConstPtr& update);
155 void createSwatches();
Ogre::ManualObject * manual_object_
std::vector< Ogre::TexturePtr > palette_textures_
QuaternionProperty * orientation_property_
std::vector< bool > color_scheme_transparency_
Ogre::TexturePtr texture_
A single element of a property tree, with a name, value, description, and possibly children...
FloatProperty * alpha_property_
Ogre::MaterialPtr material_
Property specialized to enforce floating point max/min.
Property specialized to provide max/min enforcement for integers.
ros::Subscriber update_sub_
VectorProperty * position_property_
FloatProperty * resolution_property_
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
std::vector< Swatch * > swatches
EnumProperty * color_scheme_property_
Displays a map along the XY plane.
RosTopicProperty * topic_property_
IntProperty * height_property_
Property * draw_under_property_
BoolProperty * unreliable_property_
BoolProperty * transform_timestamp_property_
Property specialized to provide getter for booleans.
Ogre::SceneNode * scene_node_
IntProperty * width_property_
nav_msgs::OccupancyGrid current_map_