GridMapDisplay.hpp
Go to the documentation of this file.
1 /*
2  * GridMapDisplay.h
3  *
4  * Created on: Aug 3, 2016
5  * Author: Philipp Krüsi, Péter Fankhauser
6  * Institute: ETH Zurich, ANYbotics
7  */
8 
9 #pragma once
10 
11 #ifndef Q_MOC_RUN
13 #include <grid_map_msgs/GridMap.h>
14 #include <boost/circular_buffer.hpp>
15 // The following replaces <rviz/message_filter_display.h>
17 #endif
18 
19 namespace Ogre {
20 class SceneNode;
21 }
22 
23 namespace rviz {
24 class BoolProperty;
25 class ColorProperty;
26 class FloatProperty;
27 class IntProperty;
28 class EnumProperty;
29 class EditableEnumProperty;
30 }
31 
33 
34 class GridMapVisual;
35 class GridMapDisplay : public MessageFilterDisplay<grid_map_msgs::GridMap>
36 {
37 Q_OBJECT
38  public:
40  virtual ~GridMapDisplay();
41 
42  protected:
43  virtual void onInitialize();
44 
45  virtual void reset();
46 
47  private Q_SLOTS:
48  void updateHistoryLength();
49  void updateHeightMode();
50  void updateColorMode();
51  void updateUseRainbow();
52  void updateAutocomputeIntensityBounds();
53  void updateVisualization();
54 
55  private:
56  // Callback for incoming ROS messages
57  void processMessage(const grid_map_msgs::GridMap::ConstPtr& msg);
58 
59  // Circular buffer for visuals
60  boost::circular_buffer<boost::shared_ptr<GridMapVisual> > visuals_;
61 
62  // Property variables
78 };
79 
80 } // end namespace grid_map_rviz_plugin
rviz::BoolProperty * showGridLinesProperty_
rviz::ColorProperty * minColorProperty_
Display subclass using a tf2_ros::MessageFilter, templated on the ROS message type.
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_


grid_map_rviz_plugin
Author(s): Philipp Krüsi , Péter Fankhauser
autogenerated on Tue Jun 1 2021 02:13:47