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
rviz::FloatProperty * skip_rate_property_
rviz::FloatProperty * alpha_property_
rviz::EnumProperty * style_property_
rviz::ColorProperty * color_property_
rviz::BoolProperty * rainbow_property_
rviz::FloatProperty * scale_property_
rviz::ColorProperty * min_color_property_
void getRainbow(float value, float &rf, float &gf, float &bf)
void processMessage(const sensor_msgs::PointCloud2::ConstPtr &msg)
boost::circular_buffer< boost::shared_ptr< NormalVisual > > visuals_
rviz::ColorProperty * max_color_property_


jsk_rviz_plugins
Author(s): Kei Okada , Yohei Kakiuchi , Shohei Fujii , Ryohei Ueda
autogenerated on Sat Mar 20 2021 03:03:18