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