point_display.h
Go to the documentation of this file.
00001 #ifndef POINT_DISPLAY_H
00002 #define POINT_DISPLAY_H
00003 
00004 #include <boost/circular_buffer.hpp>
00005 
00006 #include <geometry_msgs/PointStamped.h>
00007 #include <rviz/message_filter_display.h>
00008 
00009 
00010 namespace Ogre
00011 {
00012     class SceneNode;
00013 }
00014 
00015 namespace rviz
00016 {
00017     class ColorProperty;
00018     class FloatProperty;
00019     class IntProperty;
00020 }
00021 
00022 namespace rviz
00023 {
00024 
00025     class PointStampedVisual;
00026 
00027     class PointStampedDisplay: public rviz::MessageFilterDisplay<geometry_msgs::PointStamped>
00028     {
00029     Q_OBJECT
00030     public:
00031         // Constructor.  pluginlib::ClassLoader creates instances by calling
00032         // the default constructor, so make sure you have one.
00033         PointStampedDisplay();
00034         virtual ~PointStampedDisplay();
00035 
00036     protected:
00037         // Overrides of public virtual functions from the Display class.
00038         virtual void onInitialize();
00039         virtual void reset();
00040 
00041      private Q_SLOTS:
00042         // Helper function to apply color and alpha to all visuals.
00043         void updateColorAndAlpha();
00044         void updateHistoryLength();
00045 
00046         // Function to handle an incoming ROS message.
00047     private:
00048         void processMessage( const geometry_msgs::PointStamped::ConstPtr& msg );
00049 
00050         // Storage for the list of visuals.  It is a circular buffer where
00051         // data gets popped from the front (oldest) and pushed to the back (newest)
00052         boost::circular_buffer<boost::shared_ptr<PointStampedVisual> > visuals_;
00053 
00054         // Property objects for user-editable properties.
00055         rviz::ColorProperty *color_property_;
00056         rviz::FloatProperty *alpha_property_, *radius_property_;
00057         rviz::IntProperty *history_length_property_;
00058 
00059     };
00060 } // end namespace rviz_plugin_tutorials
00061 
00062 #endif // POINT_DISPLAY_H


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Thu Aug 27 2015 15:02:27