31 #ifndef RVIZ_GRID_CELLS_DISPLAY_H 32 #define RVIZ_GRID_CELLS_DISPLAY_H 36 #include <nav_msgs/GridCells.h> 37 #include <nav_msgs/MapMetaData.h> 44 #include <boost/shared_ptr.hpp> 57 class RosTopicProperty;
70 virtual void onInitialize();
73 virtual void fixedFrameChanged();
78 virtual void onEnable();
79 virtual void onDisable();
89 void incomingMessage(
const nav_msgs::GridCells::ConstPtr& msg );
RosTopicProperty * topic_property_
uint32_t messages_received_
message_filters::Subscriber< nav_msgs::GridCells > sub_
FloatProperty * alpha_property_
uint64_t last_frame_count_
Property specialized to enforce floating point max/min.
tf::MessageFilter< nav_msgs::GridCells > * tf_filter_
Displays a nav_msgs::GridCells message.
ColorProperty * color_property_
A visual representation of a set of points.