#include <point_display.h>

Public Member Functions | |
| virtual void | createProperties () | 
| virtual void | fixedFrameChanged () | 
| float | getAlpha () | 
| const rviz::Color & | getColor () | 
| int | getHistoryLength () const | 
| float | getRadius () | 
| const std::string & | getTopic () | 
| virtual void | onInitialize () | 
| PointStampedDisplay () | |
| virtual void | reset () | 
| void | setAlpha (float alpha) | 
| void | setColor (const rviz::Color &color) | 
| void | setHistoryLength (int history_length) | 
| void | setRadius (float radius) | 
| void | setTopic (const std::string &topic) | 
| virtual | ~PointStampedDisplay () | 
Protected Member Functions | |
| virtual void | onDisable () | 
| virtual void | onEnable () | 
Private Types | |
| typedef std::vector < PointStampedVisual * >  | MapPointStampedVisual | 
Private Member Functions | |
| void | clear () | 
| void | incomingMessage (const geometry_msgs::PointStamped::ConstPtr &msg) | 
| void | subscribe () | 
| void | unsubscribe () | 
| void | updateColorAndAlpha () | 
Private Attributes | |
| float | alpha_ | 
| rviz::FloatPropertyWPtr | alpha_property_ | 
| rviz::Color | color_ | 
| rviz::ColorPropertyWPtr | color_property_ | 
| int | history_length_ | 
| rviz::IntPropertyWPtr | history_length_property_ | 
| int | messages_received_ | 
| float | radius_ | 
| rviz::FloatPropertyWPtr | radius_property_ | 
| Ogre::SceneNode * | scene_node_ | 
| message_filters::Subscriber < geometry_msgs::PointStamped >  | sub_ | 
| tf::MessageFilter < geometry_msgs::PointStamped > *  | tf_filter_ | 
| std::string | topic_ | 
| rviz::ROSTopicStringPropertyWPtr | topic_property_ | 
| MapPointStampedVisual | visuals_ | 
Definition at line 16 of file point_display.h.
typedef std::vector<PointStampedVisual*> jsk_rviz_plugin::PointStampedDisplay::MapPointStampedVisual [private] | 
        
Definition at line 71 of file point_display.h.
Definition at line 18 of file point_display.cpp.
Definition at line 54 of file point_display.cpp.
| void jsk_rviz_plugin::PointStampedDisplay::clear | ( | void | ) |  [private] | 
        
Definition at line 64 of file point_display.cpp.
| void jsk_rviz_plugin::PointStampedDisplay::createProperties | ( | ) |  [virtual] | 
        
Reimplemented from rviz::Display.
Definition at line 271 of file point_display.cpp.
| void jsk_rviz_plugin::PointStampedDisplay::fixedFrameChanged | ( | ) |  [virtual] | 
        
Reimplemented from rviz::Display.
Definition at line 216 of file point_display.cpp.
| float jsk_rviz_plugin::PointStampedDisplay::getAlpha | ( | ) |  [inline] | 
        
Definition at line 38 of file point_display.h.
| const rviz::Color& jsk_rviz_plugin::PointStampedDisplay::getColor | ( | ) |  [inline] | 
        
Definition at line 35 of file point_display.h.
| int jsk_rviz_plugin::PointStampedDisplay::getHistoryLength | ( | ) |  const [inline] | 
        
Definition at line 44 of file point_display.h.
| float jsk_rviz_plugin::PointStampedDisplay::getRadius | ( | ) |  [inline] | 
        
Definition at line 41 of file point_display.h.
| const std::string& jsk_rviz_plugin::PointStampedDisplay::getTopic | ( | ) |  [inline] | 
        
Definition at line 32 of file point_display.h.
| void jsk_rviz_plugin::PointStampedDisplay::incomingMessage | ( | const geometry_msgs::PointStamped::ConstPtr & | msg | ) |  [private] | 
        
Definition at line 223 of file point_display.cpp.
| void jsk_rviz_plugin::PointStampedDisplay::onDisable | ( | ) |  [protected, virtual] | 
        
Implements rviz::Display.
Definition at line 208 of file point_display.cpp.
| void jsk_rviz_plugin::PointStampedDisplay::onEnable | ( | ) |  [protected, virtual] | 
        
Implements rviz::Display.
Definition at line 203 of file point_display.cpp.
| void jsk_rviz_plugin::PointStampedDisplay::onInitialize | ( | ) |  [virtual] | 
        
Reimplemented from rviz::Display.
Definition at line 28 of file point_display.cpp.
| void jsk_rviz_plugin::PointStampedDisplay::reset | ( | ) |  [virtual] | 
        
Reimplemented from rviz::Display.
Definition at line 265 of file point_display.cpp.
| void jsk_rviz_plugin::PointStampedDisplay::setAlpha | ( | float | alpha | ) | 
Definition at line 98 of file point_display.cpp.
| void jsk_rviz_plugin::PointStampedDisplay::setColor | ( | const rviz::Color & | color | ) | 
Definition at line 89 of file point_display.cpp.
| void jsk_rviz_plugin::PointStampedDisplay::setHistoryLength | ( | int | history_length | ) | 
Definition at line 129 of file point_display.cpp.
| void jsk_rviz_plugin::PointStampedDisplay::setRadius | ( | float | radius | ) | 
Definition at line 107 of file point_display.cpp.
| void jsk_rviz_plugin::PointStampedDisplay::setTopic | ( | const std::string & | topic | ) | 
Definition at line 75 of file point_display.cpp.
| void jsk_rviz_plugin::PointStampedDisplay::subscribe | ( | ) |  [private] | 
        
Definition at line 175 of file point_display.cpp.
| void jsk_rviz_plugin::PointStampedDisplay::unsubscribe | ( | ) |  [private] | 
        
Definition at line 198 of file point_display.cpp.
| void jsk_rviz_plugin::PointStampedDisplay::updateColorAndAlpha | ( | ) |  [private] | 
        
Definition at line 117 of file point_display.cpp.
float jsk_rviz_plugin::PointStampedDisplay::alpha_ [private] | 
        
Definition at line 85 of file point_display.h.
rviz::FloatPropertyWPtr jsk_rviz_plugin::PointStampedDisplay::alpha_property_ [private] | 
        
Definition at line 91 of file point_display.h.
Definition at line 83 of file point_display.h.
rviz::ColorPropertyWPtr jsk_rviz_plugin::PointStampedDisplay::color_property_ [private] | 
        
Definition at line 89 of file point_display.h.
int jsk_rviz_plugin::PointStampedDisplay::history_length_ [private] | 
        
Definition at line 86 of file point_display.h.
rviz::IntPropertyWPtr jsk_rviz_plugin::PointStampedDisplay::history_length_property_ [private] | 
        
Definition at line 92 of file point_display.h.
int jsk_rviz_plugin::PointStampedDisplay::messages_received_ [private] | 
        
Definition at line 80 of file point_display.h.
float jsk_rviz_plugin::PointStampedDisplay::radius_ [private] | 
        
Definition at line 85 of file point_display.h.
rviz::FloatPropertyWPtr jsk_rviz_plugin::PointStampedDisplay::radius_property_ [private] | 
        
Definition at line 91 of file point_display.h.
Ogre::SceneNode* jsk_rviz_plugin::PointStampedDisplay::scene_node_ [private] | 
        
Definition at line 75 of file point_display.h.
message_filters::Subscriber<geometry_msgs::PointStamped> jsk_rviz_plugin::PointStampedDisplay::sub_ [private] | 
        
Definition at line 78 of file point_display.h.
tf::MessageFilter<geometry_msgs::PointStamped>* jsk_rviz_plugin::PointStampedDisplay::tf_filter_ [private] | 
        
Definition at line 79 of file point_display.h.
Definition at line 84 of file point_display.h.
rviz::ROSTopicStringPropertyWPtr jsk_rviz_plugin::PointStampedDisplay::topic_property_ [private] | 
        
Definition at line 90 of file point_display.h.
Definition at line 72 of file point_display.h.