#include <point_display.h>

| Public Member Functions | |
| PointStampedDisplay () | |
| virtual | ~PointStampedDisplay () | 
| Protected Member Functions | |
| virtual void | onInitialize () | 
| Override this function to do subclass-specific initialization. | |
| virtual void | reset () | 
| Called to tell the display to clear its state. | |
| Private Slots | |
| void | updateColorAndAlpha () | 
| void | updateHistoryLength () | 
| Private Member Functions | |
| void | processMessage (const geometry_msgs::PointStamped::ConstPtr &msg) | 
| Private Attributes | |
| rviz::FloatProperty * | alpha_property_ | 
| rviz::ColorProperty * | color_property_ | 
| rviz::IntProperty * | history_length_property_ | 
| rviz::FloatProperty * | radius_property_ | 
| boost::circular_buffer < boost::shared_ptr < PointStampedVisual > > | visuals_ | 
Definition at line 29 of file point_display.h.
Definition at line 18 of file point_display.cpp.
| rviz::PointStampedDisplay::~PointStampedDisplay | ( | ) |  [virtual] | 
Definition at line 49 of file point_display.cpp.
| void rviz::PointStampedDisplay::onInitialize | ( | ) |  [protected, virtual] | 
Override this function to do subclass-specific initialization.
This is called after vis_manager_ and scene_manager_ are set, and before load() or setEnabled().
setName() may or may not have been called before this.
Reimplemented from rviz::MessageFilterDisplay< geometry_msgs::PointStamped >.
Definition at line 43 of file point_display.cpp.
| void rviz::PointStampedDisplay::processMessage | ( | const geometry_msgs::PointStamped::ConstPtr & | msg | ) |  [private] | 
Definition at line 81 of file point_display.cpp.
| void rviz::PointStampedDisplay::reset | ( | ) |  [protected, virtual] | 
Called to tell the display to clear its state.
Reimplemented from rviz::MessageFilterDisplay< geometry_msgs::PointStamped >.
Definition at line 54 of file point_display.cpp.
| void rviz::PointStampedDisplay::updateColorAndAlpha | ( | ) |  [private, slot] | 
Definition at line 61 of file point_display.cpp.
| void rviz::PointStampedDisplay::updateHistoryLength | ( | ) |  [private, slot] | 
Definition at line 75 of file point_display.cpp.
Definition at line 58 of file point_display.h.
Definition at line 57 of file point_display.h.
Definition at line 59 of file point_display.h.
Definition at line 58 of file point_display.h.
| boost::circular_buffer<boost::shared_ptr<PointStampedVisual> > rviz::PointStampedDisplay::visuals_  [private] | 
Definition at line 54 of file point_display.h.