Go to the documentation of this file.
2 #ifndef NORMAL_DISPLAY_H
3 #define NORMAL_DISPLAY_H
5 #include <OGRE/OgreSceneNode.h>
6 #include <OGRE/OgreSceneManager.h>
9 #include <boost/circular_buffer.hpp>
11 #include <sensor_msgs/PointCloud2.h>
59 #if ROS_VERSION_MINIMUM(1,12,0)
60 boost::circular_buffer<std::shared_ptr<NormalVisual> >
visuals_;
62 boost::circular_buffer<boost::shared_ptr<NormalVisual> >
visuals_;
68 void processMessage(
const sensor_msgs::PointCloud2::ConstPtr& msg );
rviz::ColorProperty * min_color_property_
boost::circular_buffer< boost::shared_ptr< NormalVisual > > visuals_
rviz::ColorProperty * max_color_property_
void processMessage(const sensor_msgs::PointCloud2::ConstPtr &msg)
rviz::FloatProperty * alpha_property_
rviz::FloatProperty * scale_property_
rviz::EnumProperty * style_property_
rviz::BoolProperty * rainbow_property_
void getRainbow(float value, float &rf, float &gf, float &bf)
rviz::ColorProperty * color_property_
rviz::FloatProperty * skip_rate_property_
virtual void onInitialize()
jsk_rviz_plugins
Author(s): Kei Okada
, Yohei Kakiuchi , Shohei Fujii , Ryohei Ueda
autogenerated on Fri Dec 13 2024 03:49:56