point_display.h
Go to the documentation of this file.
1 #ifndef POINT_DISPLAY_H
2 #define POINT_DISPLAY_H
3 
4 #ifndef Q_MOC_RUN
5 #include <boost/circular_buffer.hpp>
6 #endif
7 
8 #include <geometry_msgs/PointStamped.h>
10 
11 
12 namespace Ogre
13 {
14  class SceneNode;
15 }
16 
17 namespace rviz
18 {
19  class ColorProperty;
20  class FloatProperty;
21  class IntProperty;
22 }
23 
24 namespace rviz
25 {
26 
27  class PointStampedVisual;
28 
29  class PointStampedDisplay: public rviz::MessageFilterDisplay<geometry_msgs::PointStamped>
30  {
31  Q_OBJECT
32  public:
33  // Constructor. pluginlib::ClassLoader creates instances by calling
34  // the default constructor, so make sure you have one.
36  virtual ~PointStampedDisplay();
37 
38  protected:
39  // Overrides of public virtual functions from the Display class.
40  virtual void onInitialize();
41  virtual void reset();
42 
43  private Q_SLOTS:
44  // Helper function to apply color and alpha to all visuals.
45  void updateColorAndAlpha();
46  void updateHistoryLength();
47 
48  // Function to handle an incoming ROS message.
49  private:
50  void processMessage( const geometry_msgs::PointStamped::ConstPtr& msg );
51 
52  // Storage for the list of visuals. It is a circular buffer where
53  // data gets popped from the front (oldest) and pushed to the back (newest)
54  boost::circular_buffer<boost::shared_ptr<PointStampedVisual> > visuals_;
55 
56  // Property objects for user-editable properties.
60 
61  };
62 } // end namespace rviz_plugin_tutorials
63 
64 #endif // POINT_DISPLAY_H
boost::circular_buffer< boost::shared_ptr< PointStampedVisual > > visuals_
Definition: point_display.h:54
Property specialized to enforce floating point max/min.
Property specialized to provide max/min enforcement for integers.
Definition: int_property.h:38
Display subclass using a tf::MessageFilter, templated on the ROS message type.
rviz::FloatProperty * radius_property_
Definition: point_display.h:58
rviz::IntProperty * history_length_property_
Definition: point_display.h:59
rviz::ColorProperty * color_property_
Definition: point_display.h:57


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Wed Aug 28 2019 04:01:51