Classes | Public Types | Public Member Functions | Protected Slots | Protected Member Functions | Private Member Functions | Private Attributes | List of all members
mapviz_plugins::PointCloud2Plugin Class Reference

#include <pointcloud2_plugin.h>

Inheritance diagram for mapviz_plugins::PointCloud2Plugin:
Inheritance graph
[legend]

Classes

struct  FieldInfo
 
struct  Scan
 
struct  StampedPoint
 

Public Types

enum  { COLOR_FLAT = 0, COLOR_Z = 3 }
 

Public Member Functions

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 ()
 
- Public Member Functions inherited from mapviz::MapvizPlugin
int DrawOrder () const
 
void DrawPlugin (double x, double y, double scale)
 
bool GetTransform (const ros::Time &stamp, swri_transform_util::Transform &transform, bool use_latest_transforms=true)
 
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 SetUseLatestTransforms (bool value)
 
void SetVisible (bool visible)
 
std::string Type () const
 
bool Visible () const
 
virtual ~MapvizPlugin ()
 

Protected Slots

void AlphaEdited (double new_value)
 
void BufferSizeChanged (int value)
 
void ClearPointClouds ()
 
void ColorTransformerChanged (int index)
 
void DrawIcon ()
 
void MaxValueChanged (double value)
 
void MinValueChanged (double value)
 
void PointSizeChanged (int value)
 
void ResetTransformedPointClouds ()
 
void SelectTopic ()
 
void SetSubscription (bool subscribe)
 
void TopicEdited ()
 
void UpdateColors ()
 
void UseAutomaxminChanged (int check_state)
 
void UseRainbowChanged (int check_state)
 

Protected Member Functions

void PrintError (const std::string &message)
 
void PrintInfo (const std::string &message)
 
void PrintWarning (const std::string &message)
 
- Protected Member Functions inherited from mapviz::MapvizPlugin
 MapvizPlugin ()
 

Private Member Functions

QColor CalculateColor (const StampedPoint &point)
 
void PointCloud2Callback (const sensor_msgs::PointCloud2ConstPtr &scan)
 
float PointFeature (const uint8_t *, const FieldInfo &)
 
void UpdateMinMaxWidgets ()
 

Private Attributes

double alpha_
 
size_t buffer_size_
 
QWidget * config_widget_
 
bool has_message_
 
std::vector< double > max_
 
double max_value_
 
std::vector< double > min_
 
double min_value_
 
bool need_minmax_
 
bool need_new_list_
 
bool new_topic_
 
size_t num_of_feats_
 
ros::Subscriber pc2_sub_
 
size_t point_size_
 
std::string saved_color_transformer_
 
QMutex scan_mutex_
 
std::deque< Scanscans_
 
std::string topic_
 
Ui::PointCloud2_config ui_
 

Additional Inherited Members

- Public Slots inherited from mapviz::MapvizPlugin
virtual void DrawIcon ()
 
virtual bool SupportsPainting ()
 
- Signals inherited from mapviz::MapvizPlugin
void DrawOrderChanged (int draw_order)
 
void SizeChanged ()
 
void TargetFrameChanged (const std::string &target_frame)
 
void UseLatestTransformsChanged (bool use_latest_transforms)
 
void VisibleChanged (bool visible)
 
- Static Public Member Functions inherited from mapviz::MapvizPlugin
static void PrintErrorHelper (QLabel *status_label, const std::string &message, double throttle=0.0)
 
static void PrintInfoHelper (QLabel *status_label, const std::string &message, double throttle=0.0)
 
static void PrintWarningHelper (QLabel *status_label, const std::string &message, double throttle=0.0)
 
- Protected Attributes inherited from mapviz::MapvizPlugin
QGLWidget * canvas_
 
int draw_order_
 
IconWidgeticon_
 
bool initialized_
 
std::string name_
 
ros::NodeHandle node_
 
std::string source_frame_
 
std::string target_frame_
 
boost::shared_ptr< tf::TransformListenertf_
 
swri_transform_util::TransformManagerPtr tf_manager_
 
std::string type_
 
bool use_latest_transforms_
 
bool visible_
 

Detailed Description

Definition at line 54 of file pointcloud2_plugin.h.

Member Enumeration Documentation

anonymous enum
Enumerator
COLOR_FLAT 
COLOR_Z 

Definition at line 65 of file pointcloud2_plugin.h.

Constructor & Destructor Documentation

mapviz_plugins::PointCloud2Plugin::PointCloud2Plugin ( )

Definition at line 65 of file pointcloud2_plugin.cpp.

mapviz_plugins::PointCloud2Plugin::~PointCloud2Plugin ( )
virtual

Definition at line 173 of file pointcloud2_plugin.cpp.

Member Function Documentation

void mapviz_plugins::PointCloud2Plugin::AlphaEdited ( double  value)
protectedslot

Coerces alpha to [0.0, 1.0] and stores it in alpha_

Definition at line 860 of file pointcloud2_plugin.cpp.

void mapviz_plugins::PointCloud2Plugin::BufferSizeChanged ( int  value)
protectedslot

Definition at line 388 of file pointcloud2_plugin.cpp.

QColor mapviz_plugins::PointCloud2Plugin::CalculateColor ( const StampedPoint point)
private

Definition at line 248 of file pointcloud2_plugin.cpp.

void mapviz_plugins::PointCloud2Plugin::ClearHistory ( )
virtual

Reimplemented from mapviz::MapvizPlugin.

Definition at line 177 of file pointcloud2_plugin.cpp.

void mapviz_plugins::PointCloud2Plugin::ClearPointClouds ( )
protectedslot

Definition at line 228 of file pointcloud2_plugin.cpp.

void mapviz_plugins::PointCloud2Plugin::ColorTransformerChanged ( int  index)
protectedslot

Definition at line 819 of file pointcloud2_plugin.cpp.

void mapviz_plugins::PointCloud2Plugin::Draw ( double  x,
double  y,
double  scale 
)
virtual

Implements mapviz::MapvizPlugin.

Definition at line 636 of file pointcloud2_plugin.cpp.

void mapviz_plugins::PointCloud2Plugin::DrawIcon ( )
protectedslot

Definition at line 183 of file pointcloud2_plugin.cpp.

QWidget * mapviz_plugins::PointCloud2Plugin::GetConfigWidget ( QWidget *  parent)
virtual

Reimplemented from mapviz::MapvizPlugin.

Definition at line 620 of file pointcloud2_plugin.cpp.

bool mapviz_plugins::PointCloud2Plugin::Initialize ( QGLWidget *  canvas)
virtual

Implements mapviz::MapvizPlugin.

Definition at line 627 of file pointcloud2_plugin.cpp.

void mapviz_plugins::PointCloud2Plugin::LoadConfig ( const YAML::Node &  node,
const std::string &  path 
)
virtual

Implements mapviz::MapvizPlugin.

Definition at line 730 of file pointcloud2_plugin.cpp.

void mapviz_plugins::PointCloud2Plugin::MaxValueChanged ( double  value)
protectedslot

Definition at line 382 of file pointcloud2_plugin.cpp.

void mapviz_plugins::PointCloud2Plugin::MinValueChanged ( double  value)
protectedslot

Definition at line 376 of file pointcloud2_plugin.cpp.

void mapviz_plugins::PointCloud2Plugin::PointCloud2Callback ( const sensor_msgs::PointCloud2ConstPtr &  scan)
private

Definition at line 411 of file pointcloud2_plugin.cpp.

float mapviz_plugins::PointCloud2Plugin::PointFeature ( const uint8_t *  data,
const FieldInfo feature_info 
)
private

Definition at line 579 of file pointcloud2_plugin.cpp.

void mapviz_plugins::PointCloud2Plugin::PointSizeChanged ( int  value)
protectedslot

Definition at line 404 of file pointcloud2_plugin.cpp.

void mapviz_plugins::PointCloud2Plugin::PrintError ( const std::string &  message)
protectedvirtual

Implements mapviz::MapvizPlugin.

Definition at line 605 of file pointcloud2_plugin.cpp.

void mapviz_plugins::PointCloud2Plugin::PrintInfo ( const std::string &  message)
protectedvirtual

Implements mapviz::MapvizPlugin.

Definition at line 610 of file pointcloud2_plugin.cpp.

void mapviz_plugins::PointCloud2Plugin::PrintWarning ( const std::string &  message)
protectedvirtual

Implements mapviz::MapvizPlugin.

Definition at line 615 of file pointcloud2_plugin.cpp.

void mapviz_plugins::PointCloud2Plugin::ResetTransformedPointClouds ( )
protectedslot

Definition at line 217 of file pointcloud2_plugin.cpp.

void mapviz_plugins::PointCloud2Plugin::SaveConfig ( YAML::Emitter &  emitter,
const std::string &  path 
)
virtual

Implements mapviz::MapvizPlugin.

Definition at line 865 of file pointcloud2_plugin.cpp.

void mapviz_plugins::PointCloud2Plugin::SelectTopic ( )
protectedslot

Definition at line 345 of file pointcloud2_plugin.cpp.

void mapviz_plugins::PointCloud2Plugin::SetSubscription ( bool  subscribe)
protectedslot

Definition at line 234 of file pointcloud2_plugin.cpp.

void mapviz_plugins::PointCloud2Plugin::Shutdown ( )
inlinevirtual

Implements mapviz::MapvizPlugin.

Definition at line 75 of file pointcloud2_plugin.h.

void mapviz_plugins::PointCloud2Plugin::TopicEdited ( )
protectedslot

Definition at line 358 of file pointcloud2_plugin.cpp.

void mapviz_plugins::PointCloud2Plugin::Transform ( )
virtual

Implements mapviz::MapvizPlugin.

Definition at line 688 of file pointcloud2_plugin.cpp.

void mapviz_plugins::PointCloud2Plugin::UpdateColors ( )
protectedslot

Definition at line 324 of file pointcloud2_plugin.cpp.

void mapviz_plugins::PointCloud2Plugin::UpdateMinMaxWidgets ( )
private

Definition at line 826 of file pointcloud2_plugin.cpp.

void mapviz_plugins::PointCloud2Plugin::UseAutomaxminChanged ( int  check_state)
protectedslot

Definition at line 675 of file pointcloud2_plugin.cpp.

void mapviz_plugins::PointCloud2Plugin::UseRainbowChanged ( int  check_state)
protectedslot

Definition at line 669 of file pointcloud2_plugin.cpp.

Member Data Documentation

double mapviz_plugins::PointCloud2Plugin::alpha_
private

Definition at line 143 of file pointcloud2_plugin.h.

size_t mapviz_plugins::PointCloud2Plugin::buffer_size_
private

Definition at line 147 of file pointcloud2_plugin.h.

QWidget* mapviz_plugins::PointCloud2Plugin::config_widget_
private

Definition at line 140 of file pointcloud2_plugin.h.

bool mapviz_plugins::PointCloud2Plugin::has_message_
private

Definition at line 149 of file pointcloud2_plugin.h.

std::vector<double> mapviz_plugins::PointCloud2Plugin::max_
private

Definition at line 154 of file pointcloud2_plugin.h.

double mapviz_plugins::PointCloud2Plugin::max_value_
private

Definition at line 144 of file pointcloud2_plugin.h.

std::vector<double> mapviz_plugins::PointCloud2Plugin::min_
private

Definition at line 155 of file pointcloud2_plugin.h.

double mapviz_plugins::PointCloud2Plugin::min_value_
private

Definition at line 145 of file pointcloud2_plugin.h.

bool mapviz_plugins::PointCloud2Plugin::need_minmax_
private

Definition at line 153 of file pointcloud2_plugin.h.

bool mapviz_plugins::PointCloud2Plugin::need_new_list_
private

Definition at line 151 of file pointcloud2_plugin.h.

bool mapviz_plugins::PointCloud2Plugin::new_topic_
private

Definition at line 148 of file pointcloud2_plugin.h.

size_t mapviz_plugins::PointCloud2Plugin::num_of_feats_
private

Definition at line 150 of file pointcloud2_plugin.h.

ros::Subscriber mapviz_plugins::PointCloud2Plugin::pc2_sub_
private

Definition at line 160 of file pointcloud2_plugin.h.

size_t mapviz_plugins::PointCloud2Plugin::point_size_
private

Definition at line 146 of file pointcloud2_plugin.h.

std::string mapviz_plugins::PointCloud2Plugin::saved_color_transformer_
private

Definition at line 152 of file pointcloud2_plugin.h.

QMutex mapviz_plugins::PointCloud2Plugin::scan_mutex_
private

Definition at line 162 of file pointcloud2_plugin.h.

std::deque<Scan> mapviz_plugins::PointCloud2Plugin::scans_
private

Definition at line 159 of file pointcloud2_plugin.h.

std::string mapviz_plugins::PointCloud2Plugin::topic_
private

Definition at line 142 of file pointcloud2_plugin.h.

Ui::PointCloud2_config mapviz_plugins::PointCloud2Plugin::ui_
private

Definition at line 139 of file pointcloud2_plugin.h.


The documentation for this class was generated from the following files:


mapviz_plugins
Author(s): Marc Alban
autogenerated on Fri Mar 19 2021 02:44:32