normal_display.h
Go to the documentation of this file.
1 // -*- mode: C++ -*-
2 #ifndef NORMAL_DISPLAY_H
3 #define NORMAL_DISPLAY_H
4 #ifndef Q_MOC_RUN
5 #include <OGRE/OgreSceneNode.h>
6 #include <OGRE/OgreSceneManager.h>
7 #include <QColor>
8 
9 #include <boost/circular_buffer.hpp>
10 
11 #include <sensor_msgs/PointCloud2.h>
12 
15 #include <rviz/validate_floats.h>
17 #include <rviz/frame_manager.h>
23 #include "normal_visual.h"
24 #endif
25 
26 namespace jsk_rviz_plugins
27 {
28 
29 class NormalDisplay: public rviz::MessageFilterDisplay<sensor_msgs::PointCloud2>
30 {
31 Q_OBJECT
32 public:
33  NormalDisplay();
34  virtual ~NormalDisplay();
43  float skip_rate_;
44  float scale_;
45  float alpha_;
46 
47  enum ColorTypes{
52  };
53 
54 protected:
55  virtual void onInitialize();
56 
57  virtual void reset();
58 
59 #if ROS_VERSION_MINIMUM(1,12,0)
60  boost::circular_buffer<std::shared_ptr<NormalVisual> > visuals_;
61 #else
62  boost::circular_buffer<boost::shared_ptr<NormalVisual> > visuals_;
63 #endif
64 
65 
66  // Function to handle an incoming ROS message.
67 private Q_SLOTS:
68  void processMessage( const sensor_msgs::PointCloud2::ConstPtr& msg );
69  void updateStyle();
70  void updateSkipRate();
71  void updateRainbow();
72  void updateScale();
73  void updateAlpha();
74  void getRainbow(float value , float& rf, float& gf, float& bf);
75 };
76 
77 }
78 
79 #endif
jsk_rviz_plugins::NormalDisplay::DIRECTION_COLOR
@ DIRECTION_COLOR
Definition: normal_display.h:50
rviz::MessageFilterDisplay
jsk_rviz_plugins::NormalDisplay::min_color_property_
rviz::ColorProperty * min_color_property_
Definition: normal_display.h:37
jsk_rviz_plugins::NormalDisplay::visuals_
boost::circular_buffer< boost::shared_ptr< NormalVisual > > visuals_
Definition: normal_display.h:62
jsk_rviz_plugins::NormalDisplay::updateAlpha
void updateAlpha()
Definition: normal_display.cpp:85
bounding_box_sample.value
value
Definition: bounding_box_sample.py:38
jsk_rviz_plugins::NormalDisplay::max_color_property_
rviz::ColorProperty * max_color_property_
Definition: normal_display.h:38
rviz::BoolProperty
int_property.h
frame_manager.h
validate_floats.h
enum_property.h
jsk_rviz_plugins::NormalDisplay::~NormalDisplay
virtual ~NormalDisplay()
Definition: normal_display.cpp:129
jsk_rviz_plugins::NormalDisplay::processMessage
void processMessage(const sensor_msgs::PointCloud2::ConstPtr &msg)
Definition: normal_display.cpp:143
float_property.h
rviz::ColorProperty
visualization_manager.h
rviz::EnumProperty
rviz::FloatProperty
jsk_rviz_plugins::NormalDisplay::ColorTypes
ColorTypes
Definition: normal_display.h:47
bool_property.h
jsk_rviz_plugins::NormalDisplay::skip_rate_
float skip_rate_
Definition: normal_display.h:43
jsk_rviz_plugins::NormalDisplay::reset
virtual void reset()
Definition: normal_display.cpp:136
jsk_rviz_plugins::NormalDisplay::alpha_
float alpha_
Definition: normal_display.h:45
jsk_rviz_plugins::NormalDisplay::NormalDisplay
NormalDisplay()
Definition: normal_display.cpp:9
jsk_rviz_plugins::NormalDisplay::alpha_property_
rviz::FloatProperty * alpha_property_
Definition: normal_display.h:42
message_filter_display.h
jsk_rviz_plugins::NormalDisplay::updateSkipRate
void updateSkipRate()
Definition: normal_display.cpp:89
jsk_rviz_plugins::NormalDisplay::updateScale
void updateScale()
Definition: normal_display.cpp:81
jsk_rviz_plugins::NormalDisplay::CURVATURE_COLOR
@ CURVATURE_COLOR
Definition: normal_display.h:51
jsk_rviz_plugins::NormalDisplay::scale_property_
rviz::FloatProperty * scale_property_
Definition: normal_display.h:41
jsk_rviz_plugins::NormalDisplay::updateRainbow
void updateRainbow()
Definition: normal_display.cpp:71
jsk_rviz_plugins::NormalDisplay::style_property_
rviz::EnumProperty * style_property_
Definition: normal_display.h:35
point_cloud_transformers.h
jsk_rviz_plugins::NormalDisplay::rainbow_property_
rviz::BoolProperty * rainbow_property_
Definition: normal_display.h:40
jsk_rviz_plugins::NormalDisplay::updateStyle
void updateStyle()
Definition: normal_display.cpp:93
jsk_rviz_plugins::NormalDisplay::FLAT_COLOR
@ FLAT_COLOR
Definition: normal_display.h:49
jsk_rviz_plugins::NormalDisplay::scale_
float scale_
Definition: normal_display.h:44
jsk_rviz_plugins::NormalDisplay
Definition: normal_display.h:29
jsk_rviz_plugins::NormalDisplay::getRainbow
void getRainbow(float value, float &rf, float &gf, float &bf)
Definition: normal_display.cpp:56
jsk_rviz_plugins::NormalDisplay::POINTS_COLOR
@ POINTS_COLOR
Definition: normal_display.h:48
jsk_rviz_plugins::NormalDisplay::color_property_
rviz::ColorProperty * color_property_
Definition: normal_display.h:36
jsk_rviz_plugins::NormalDisplay::skip_rate_property_
rviz::FloatProperty * skip_rate_property_
Definition: normal_display.h:39
jsk_rviz_plugins
Definition: __init__.py:1
jsk_rviz_plugins::NormalDisplay::onInitialize
virtual void onInitialize()
Definition: normal_display.cpp:124
normal_visual.h
color_property.h


jsk_rviz_plugins
Author(s): Kei Okada , Yohei Kakiuchi , Shohei Fujii , Ryohei Ueda
autogenerated on Tue Dec 10 2024 03:48:24