13 #include <grid_map_msgs/GridMap.h> 14 #include <boost/circular_buffer.hpp> 29 class EditableEnumProperty;
43 virtual void onInitialize();
48 void updateHistoryLength();
49 void updateHeightMode();
50 void updateColorMode();
51 void updateUseRainbow();
52 void updateAutocomputeIntensityBounds();
53 void updateVisualization();
57 void processMessage(
const grid_map_msgs::GridMap::ConstPtr& msg);
60 boost::circular_buffer<boost::shared_ptr<GridMapVisual> >
visuals_;
rviz::ColorProperty * colorProperty_
rviz::BoolProperty * showGridLinesProperty_
rviz::ColorProperty * minColorProperty_
Display subclass using a tf2_ros::MessageFilter, templated on the ROS message type.
rviz::FloatProperty * alphaProperty_
rviz::EnumProperty * colorModeProperty_
rviz::IntProperty * historyLengthProperty_
rviz::BoolProperty * autocomputeIntensityBoundsProperty_
rviz::ColorProperty * maxColorProperty_
rviz::BoolProperty * invertRainbowProperty_
rviz::BoolProperty * useRainbowProperty_
rviz::EnumProperty * heightModeProperty_
rviz::FloatProperty * minIntensityProperty_
rviz::EditableEnumProperty * colorTransformerProperty_
boost::circular_buffer< boost::shared_ptr< GridMapVisual > > visuals_
rviz::FloatProperty * maxIntensityProperty_
rviz::EditableEnumProperty * heightTransformerProperty_