13 #include <grid_map_msgs/GridMap.h> 14 #include <boost/circular_buffer.hpp> 29 class EditableEnumProperty;
43 virtual void onInitialize();
45 virtual void onEnable();
47 virtual void onDisable();
53 void process(
const grid_map_msgs::GridMap::ConstPtr& msg);
56 void updateHistoryLength();
57 void updateHeightMode();
58 void updateColorMode();
59 void updateUseColorMap();
60 void updateAutocomputeIntensityBounds();
61 void updateVisualization();
62 void updateColorMapList();
63 void updateGridLines();
65 void onProcessMessage(
const grid_map_msgs::GridMap::ConstPtr& msg);
69 void processMessage(
const grid_map_msgs::GridMap::ConstPtr& msg);
72 std::atomic<bool> isEnabled_{
true};
75 boost::circular_buffer<boost::shared_ptr<GridMapVisual> >
visuals_;
rviz::ColorProperty * colorProperty_
rviz::BoolProperty * showGridLinesProperty_
rviz::EditableEnumProperty * colorMapProperty_
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::BoolProperty * useColorMapProperty_
rviz::ColorProperty * maxColorProperty_
rviz::FloatProperty * gridLinesThicknessProperty_
rviz::IntProperty * gridCellDecimationProperty_
rviz::EnumProperty * heightModeProperty_
rviz::FloatProperty * minIntensityProperty_
rviz::EditableEnumProperty * colorTransformerProperty_
rviz::BoolProperty * invertColorMapProperty_
boost::circular_buffer< boost::shared_ptr< GridMapVisual > > visuals_
rviz::FloatProperty * maxIntensityProperty_
rviz::EditableEnumProperty * heightTransformerProperty_