#include <normal_display.h>

| Public Types | |
| enum | ColorTypes { POINTS_COLOR, FLAT_COLOR, DIRECTION_COLOR, CURVATURE_COLOR } | 
| Public Member Functions | |
| NormalDisplay () | |
| virtual | ~NormalDisplay () | 
| Public Attributes | |
| float | alpha_ | 
| rviz::FloatProperty * | alpha_property_ | 
| rviz::ColorProperty * | color_property_ | 
| rviz::ColorProperty * | max_color_property_ | 
| rviz::ColorProperty * | min_color_property_ | 
| rviz::BoolProperty * | rainbow_property_ | 
| float | scale_ | 
| rviz::FloatProperty * | scale_property_ | 
| float | skip_rate_ | 
| rviz::FloatProperty * | skip_rate_property_ | 
| rviz::EnumProperty * | style_property_ | 
| Protected Member Functions | |
| virtual void | onInitialize () | 
| virtual void | reset () | 
| Protected Attributes | |
| boost::circular_buffer < boost::shared_ptr < NormalVisual > > | visuals_ | 
| Private Slots | |
| void | getRainbow (float value, float &rf, float &gf, float &bf) | 
| void | processMessage (const sensor_msgs::PointCloud2::ConstPtr &msg) | 
| void | updateAlpha () | 
| void | updateRainbow () | 
| void | updateScale () | 
| void | updateSkipRate () | 
| void | updateStyle () | 
Definition at line 27 of file normal_display.h.
Definition at line 45 of file normal_display.h.
Definition at line 9 of file normal_display.cpp.
| jsk_rviz_plugin::NormalDisplay::~NormalDisplay | ( | ) |  [virtual] | 
Definition at line 129 of file normal_display.cpp.
| void jsk_rviz_plugin::NormalDisplay::getRainbow | ( | float | value, | 
| float & | rf, | ||
| float & | gf, | ||
| float & | bf | ||
| ) |  [private, slot] | 
Definition at line 56 of file normal_display.cpp.
| void jsk_rviz_plugin::NormalDisplay::onInitialize | ( | ) |  [protected, virtual] | 
Reimplemented from rviz::MessageFilterDisplay< sensor_msgs::PointCloud2 >.
Definition at line 124 of file normal_display.cpp.
| void jsk_rviz_plugin::NormalDisplay::processMessage | ( | const sensor_msgs::PointCloud2::ConstPtr & | msg | ) |  [private, slot] | 
Definition at line 143 of file normal_display.cpp.
| void jsk_rviz_plugin::NormalDisplay::reset | ( | ) |  [protected, virtual] | 
Reimplemented from rviz::MessageFilterDisplay< sensor_msgs::PointCloud2 >.
Definition at line 136 of file normal_display.cpp.
| void jsk_rviz_plugin::NormalDisplay::updateAlpha | ( | ) |  [private, slot] | 
Definition at line 85 of file normal_display.cpp.
| void jsk_rviz_plugin::NormalDisplay::updateRainbow | ( | ) |  [private, slot] | 
Definition at line 71 of file normal_display.cpp.
| void jsk_rviz_plugin::NormalDisplay::updateScale | ( | ) |  [private, slot] | 
Definition at line 81 of file normal_display.cpp.
| void jsk_rviz_plugin::NormalDisplay::updateSkipRate | ( | ) |  [private, slot] | 
Definition at line 89 of file normal_display.cpp.
| void jsk_rviz_plugin::NormalDisplay::updateStyle | ( | ) |  [private, slot] | 
Definition at line 93 of file normal_display.cpp.
Definition at line 43 of file normal_display.h.
Definition at line 40 of file normal_display.h.
Definition at line 34 of file normal_display.h.
Definition at line 36 of file normal_display.h.
Definition at line 35 of file normal_display.h.
Definition at line 38 of file normal_display.h.
Definition at line 42 of file normal_display.h.
Definition at line 39 of file normal_display.h.
Definition at line 41 of file normal_display.h.
Definition at line 37 of file normal_display.h.
Definition at line 33 of file normal_display.h.
| boost::circular_buffer<boost::shared_ptr<NormalVisual> > jsk_rviz_plugin::NormalDisplay::visuals_  [protected] | 
Definition at line 57 of file normal_display.h.