#include <pointcloud2_plugin.h>
|  | 
| void | ClearHistory () | 
|  | 
| void | Draw (double x, double y, double scale) | 
|  | 
| QWidget * | GetConfigWidget (QWidget *parent) | 
|  | 
| bool | Initialize (QGLWidget *canvas) | 
|  | 
| void | LoadConfig (const YAML::Node &node, const std::string &path) | 
|  | 
|  | PointCloud2Plugin () | 
|  | 
| void | SaveConfig (YAML::Emitter &emitter, const std::string &path) | 
|  | 
| void | Shutdown () | 
|  | 
| void | Transform () | 
|  | 
| virtual | ~PointCloud2Plugin () | 
|  | 
| int | DrawOrder () const | 
|  | 
| void | DrawPlugin (double x, double y, double scale) | 
|  | 
| bool | GetTransform (const ros::Time &stamp, swri_transform_util::Transform &transform) | 
|  | 
| bool | GetTransform (const std::string &source, const ros::Time &stamp, swri_transform_util::Transform &transform) | 
|  | 
| virtual bool | Initialize (boost::shared_ptr< tf::TransformListener > tf_listener, swri_transform_util::TransformManagerPtr tf_manager, QGLWidget *canvas) | 
|  | 
| std::string | Name () const | 
|  | 
| virtual void | Paint (QPainter *painter, double x, double y, double scale) | 
|  | 
| void | PaintPlugin (QPainter *painter, double x, double y, double scale) | 
|  | 
| void | PrintMeasurements () | 
|  | 
| void | SetDrawOrder (int order) | 
|  | 
| void | SetIcon (IconWidget *icon) | 
|  | 
| void | SetName (const std::string &name) | 
|  | 
| virtual void | SetNode (const ros::NodeHandle &node) | 
|  | 
| void | SetTargetFrame (std::string frame_id) | 
|  | 
| void | SetType (const std::string &type) | 
|  | 
| void | SetVisible (bool visible) | 
|  | 
| std::string | Type () const | 
|  | 
| bool | Visible () const | 
|  | 
| virtual | ~MapvizPlugin () | 
|  | 
Definition at line 54 of file pointcloud2_plugin.h.
 
◆ anonymous enum
◆ PointCloud2Plugin()
      
        
          | mapviz_plugins::PointCloud2Plugin::PointCloud2Plugin | ( |  | ) |  | 
      
 
 
◆ ~PointCloud2Plugin()
  
  | 
        
          | mapviz_plugins::PointCloud2Plugin::~PointCloud2Plugin | ( |  | ) |  |  | virtual | 
 
 
◆ AlphaEdited
  
  | 
        
          | void mapviz_plugins::PointCloud2Plugin::AlphaEdited | ( | double | value | ) |  |  | protectedslot | 
 
 
◆ BufferSizeChanged
  
  | 
        
          | void mapviz_plugins::PointCloud2Plugin::BufferSizeChanged | ( | int | value | ) |  |  | protectedslot | 
 
 
◆ CalculateColor()
  
  | 
        
          | QColor mapviz_plugins::PointCloud2Plugin::CalculateColor | ( | const StampedPoint & | point | ) |  |  | private | 
 
 
◆ ClearHistory()
  
  | 
        
          | void mapviz_plugins::PointCloud2Plugin::ClearHistory | ( |  | ) |  |  | virtual | 
 
 
◆ ClearPointClouds
  
  | 
        
          | void mapviz_plugins::PointCloud2Plugin::ClearPointClouds | ( |  | ) |  |  | protectedslot | 
 
 
◆ ColorTransformerChanged
  
  | 
        
          | void mapviz_plugins::PointCloud2Plugin::ColorTransformerChanged | ( | int | index | ) |  |  | protectedslot | 
 
 
◆ Draw()
  
  | 
        
          | void mapviz_plugins::PointCloud2Plugin::Draw | ( | double | x, |  
          |  |  | double | y, |  
          |  |  | double | scale |  
          |  | ) |  |  |  | virtual | 
 
 
◆ DrawIcon
  
  | 
        
          | void mapviz_plugins::PointCloud2Plugin::DrawIcon | ( |  | ) |  |  | protectedslot | 
 
 
◆ GetConfigWidget()
  
  | 
        
          | QWidget * mapviz_plugins::PointCloud2Plugin::GetConfigWidget | ( | QWidget * | parent | ) |  |  | virtual | 
 
 
◆ Initialize()
  
  | 
        
          | bool mapviz_plugins::PointCloud2Plugin::Initialize | ( | QGLWidget * | canvas | ) |  |  | virtual | 
 
 
◆ LoadConfig()
  
  | 
        
          | void mapviz_plugins::PointCloud2Plugin::LoadConfig | ( | const YAML::Node & | node, |  
          |  |  | const std::string & | path |  
          |  | ) |  |  |  | virtual | 
 
 
◆ MaxValueChanged
  
  | 
        
          | void mapviz_plugins::PointCloud2Plugin::MaxValueChanged | ( | double | value | ) |  |  | protectedslot | 
 
 
◆ MinValueChanged
  
  | 
        
          | void mapviz_plugins::PointCloud2Plugin::MinValueChanged | ( | double | value | ) |  |  | protectedslot | 
 
 
◆ PointCloud2Callback()
  
  | 
        
          | void mapviz_plugins::PointCloud2Plugin::PointCloud2Callback | ( | const sensor_msgs::PointCloud2ConstPtr & | scan | ) |  |  | private | 
 
 
◆ PointFeature()
  
  | 
        
          | float mapviz_plugins::PointCloud2Plugin::PointFeature | ( | const uint8_t * | data, |  
          |  |  | const FieldInfo & | feature_info |  
          |  | ) |  |  |  | private | 
 
 
◆ PointSizeChanged
  
  | 
        
          | void mapviz_plugins::PointCloud2Plugin::PointSizeChanged | ( | int | value | ) |  |  | protectedslot | 
 
 
◆ PrintError()
  
  | 
        
          | void mapviz_plugins::PointCloud2Plugin::PrintError | ( | const std::string & | message | ) |  |  | protectedvirtual | 
 
 
◆ PrintInfo()
  
  | 
        
          | void mapviz_plugins::PointCloud2Plugin::PrintInfo | ( | const std::string & | message | ) |  |  | protectedvirtual | 
 
 
◆ PrintWarning()
  
  | 
        
          | void mapviz_plugins::PointCloud2Plugin::PrintWarning | ( | const std::string & | message | ) |  |  | protectedvirtual | 
 
 
◆ ResetTransformedPointClouds
  
  | 
        
          | void mapviz_plugins::PointCloud2Plugin::ResetTransformedPointClouds | ( |  | ) |  |  | protectedslot | 
 
 
◆ SaveConfig()
  
  | 
        
          | void mapviz_plugins::PointCloud2Plugin::SaveConfig | ( | YAML::Emitter & | emitter, |  
          |  |  | const std::string & | path |  
          |  | ) |  |  |  | virtual | 
 
 
◆ SelectTopic
  
  | 
        
          | void mapviz_plugins::PointCloud2Plugin::SelectTopic | ( |  | ) |  |  | protectedslot | 
 
 
◆ SetSubscription
  
  | 
        
          | void mapviz_plugins::PointCloud2Plugin::SetSubscription | ( | bool | subscribe | ) |  |  | protectedslot | 
 
 
◆ Shutdown()
  
  | 
        
          | void mapviz_plugins::PointCloud2Plugin::Shutdown | ( |  | ) |  |  | inlinevirtual | 
 
 
◆ TopicEdited
  
  | 
        
          | void mapviz_plugins::PointCloud2Plugin::TopicEdited | ( |  | ) |  |  | protectedslot | 
 
 
◆ Transform()
  
  | 
        
          | void mapviz_plugins::PointCloud2Plugin::Transform | ( |  | ) |  |  | virtual | 
 
 
◆ UpdateColors
  
  | 
        
          | void mapviz_plugins::PointCloud2Plugin::UpdateColors | ( |  | ) |  |  | protectedslot | 
 
 
◆ UpdateMinMaxWidgets()
  
  | 
        
          | void mapviz_plugins::PointCloud2Plugin::UpdateMinMaxWidgets | ( |  | ) |  |  | private | 
 
 
◆ UseAutomaxminChanged
  
  | 
        
          | void mapviz_plugins::PointCloud2Plugin::UseAutomaxminChanged | ( | int | check_state | ) |  |  | protectedslot | 
 
 
◆ UseRainbowChanged
  
  | 
        
          | void mapviz_plugins::PointCloud2Plugin::UseRainbowChanged | ( | int | check_state | ) |  |  | protectedslot | 
 
 
◆ alpha_
  
  | 
        
          | double mapviz_plugins::PointCloud2Plugin::alpha_ |  | private | 
 
 
◆ buffer_size_
  
  | 
        
          | size_t mapviz_plugins::PointCloud2Plugin::buffer_size_ |  | private | 
 
 
◆ config_widget_
  
  | 
        
          | QWidget* mapviz_plugins::PointCloud2Plugin::config_widget_ |  | private | 
 
 
◆ has_message_
  
  | 
        
          | bool mapviz_plugins::PointCloud2Plugin::has_message_ |  | private | 
 
 
◆ max_
  
  | 
        
          | std::vector<double> mapviz_plugins::PointCloud2Plugin::max_ |  | private | 
 
 
◆ max_value_
  
  | 
        
          | double mapviz_plugins::PointCloud2Plugin::max_value_ |  | private | 
 
 
◆ min_
  
  | 
        
          | std::vector<double> mapviz_plugins::PointCloud2Plugin::min_ |  | private | 
 
 
◆ min_value_
  
  | 
        
          | double mapviz_plugins::PointCloud2Plugin::min_value_ |  | private | 
 
 
◆ need_minmax_
  
  | 
        
          | bool mapviz_plugins::PointCloud2Plugin::need_minmax_ |  | private | 
 
 
◆ need_new_list_
  
  | 
        
          | bool mapviz_plugins::PointCloud2Plugin::need_new_list_ |  | private | 
 
 
◆ new_topic_
  
  | 
        
          | bool mapviz_plugins::PointCloud2Plugin::new_topic_ |  | private | 
 
 
◆ num_of_feats_
  
  | 
        
          | size_t mapviz_plugins::PointCloud2Plugin::num_of_feats_ |  | private | 
 
 
◆ pc2_sub_
◆ point_size_
  
  | 
        
          | size_t mapviz_plugins::PointCloud2Plugin::point_size_ |  | private | 
 
 
◆ saved_color_transformer_
  
  | 
        
          | std::string mapviz_plugins::PointCloud2Plugin::saved_color_transformer_ |  | private | 
 
 
◆ scan_mutex_
  
  | 
        
          | QMutex mapviz_plugins::PointCloud2Plugin::scan_mutex_ |  | private | 
 
 
◆ scans_
  
  | 
        
          | std::deque<Scan> mapviz_plugins::PointCloud2Plugin::scans_ |  | private | 
 
 
◆ topic_
  
  | 
        
          | std::string mapviz_plugins::PointCloud2Plugin::topic_ |  | private | 
 
 
◆ ui_
  
  | 
        
          | Ui::PointCloud2_config mapviz_plugins::PointCloud2Plugin::ui_ |  | private | 
 
 
The documentation for this class was generated from the following files: