#include <pointcloud2_plugin.h>
Classes | |
struct | FieldInfo |
struct | Scan |
struct | StampedPoint |
Public Types | |
enum | { COLOR_FLAT = 0, COLOR_Z = 3 } |
Public Member Functions | |
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 () |
Protected Slots | |
void | AlphaEdited () |
void | BufferSizeChanged (int value) |
void | ColorTransformerChanged (int index) |
void | DrawIcon () |
void | MaxValueChanged (double value) |
void | MinValueChanged (double value) |
void | PointSizeChanged (int value) |
void | ResetTransformedPointClouds () |
void | SelectTopic () |
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) |
Private Member Functions | |
QColor | CalculateColor (const StampedPoint &point) |
void | PointCloud2Callback (const sensor_msgs::PointCloud2ConstPtr &scan) |
double | 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< Scan > | scans_ |
std::string | topic_ |
Ui::PointCloud2_config | ui_ |
Definition at line 54 of file pointcloud2_plugin.h.
anonymous enum |
Definition at line 65 of file pointcloud2_plugin.h.
virtual mapviz_plugins::PointCloud2Plugin::~PointCloud2Plugin | ( | ) | [virtual] |
void mapviz_plugins::PointCloud2Plugin::AlphaEdited | ( | ) | [protected, slot] |
void mapviz_plugins::PointCloud2Plugin::BufferSizeChanged | ( | int | value | ) | [protected, slot] |
QColor mapviz_plugins::PointCloud2Plugin::CalculateColor | ( | const StampedPoint & | point | ) | [private] |
void mapviz_plugins::PointCloud2Plugin::ColorTransformerChanged | ( | int | index | ) | [protected, slot] |
void mapviz_plugins::PointCloud2Plugin::Draw | ( | double | x, |
double | y, | ||
double | scale | ||
) | [virtual] |
Implements mapviz::MapvizPlugin.
void mapviz_plugins::PointCloud2Plugin::DrawIcon | ( | ) | [protected, virtual, slot] |
Reimplemented from mapviz::MapvizPlugin.
QWidget* mapviz_plugins::PointCloud2Plugin::GetConfigWidget | ( | QWidget * | parent | ) | [virtual] |
Reimplemented from mapviz::MapvizPlugin.
bool mapviz_plugins::PointCloud2Plugin::Initialize | ( | QGLWidget * | canvas | ) | [virtual] |
Implements mapviz::MapvizPlugin.
void mapviz_plugins::PointCloud2Plugin::LoadConfig | ( | const YAML::Node & | node, |
const std::string & | path | ||
) | [virtual] |
Implements mapviz::MapvizPlugin.
void mapviz_plugins::PointCloud2Plugin::MaxValueChanged | ( | double | value | ) | [protected, slot] |
void mapviz_plugins::PointCloud2Plugin::MinValueChanged | ( | double | value | ) | [protected, slot] |
void mapviz_plugins::PointCloud2Plugin::PointCloud2Callback | ( | const sensor_msgs::PointCloud2ConstPtr & | scan | ) | [private] |
double mapviz_plugins::PointCloud2Plugin::PointFeature | ( | const uint8_t * | , |
const FieldInfo & | |||
) | [private] |
void mapviz_plugins::PointCloud2Plugin::PointSizeChanged | ( | int | value | ) | [protected, slot] |
void mapviz_plugins::PointCloud2Plugin::PrintError | ( | const std::string & | message | ) | [protected, virtual] |
Implements mapviz::MapvizPlugin.
void mapviz_plugins::PointCloud2Plugin::PrintInfo | ( | const std::string & | message | ) | [protected, virtual] |
Implements mapviz::MapvizPlugin.
void mapviz_plugins::PointCloud2Plugin::PrintWarning | ( | const std::string & | message | ) | [protected, virtual] |
Implements mapviz::MapvizPlugin.
void mapviz_plugins::PointCloud2Plugin::ResetTransformedPointClouds | ( | ) | [protected, slot] |
void mapviz_plugins::PointCloud2Plugin::SaveConfig | ( | YAML::Emitter & | emitter, |
const std::string & | path | ||
) | [virtual] |
Implements mapviz::MapvizPlugin.
void mapviz_plugins::PointCloud2Plugin::SelectTopic | ( | ) | [protected, slot] |
void mapviz_plugins::PointCloud2Plugin::Shutdown | ( | ) | [inline, virtual] |
Implements mapviz::MapvizPlugin.
Definition at line 75 of file pointcloud2_plugin.h.
void mapviz_plugins::PointCloud2Plugin::TopicEdited | ( | ) | [protected, slot] |
void mapviz_plugins::PointCloud2Plugin::Transform | ( | ) | [virtual] |
Implements mapviz::MapvizPlugin.
void mapviz_plugins::PointCloud2Plugin::UpdateColors | ( | ) | [protected, slot] |
void mapviz_plugins::PointCloud2Plugin::UpdateMinMaxWidgets | ( | ) | [private] |
void mapviz_plugins::PointCloud2Plugin::UseAutomaxminChanged | ( | int | check_state | ) | [protected, slot] |
void mapviz_plugins::PointCloud2Plugin::UseRainbowChanged | ( | int | check_state | ) | [protected, slot] |
double mapviz_plugins::PointCloud2Plugin::alpha_ [private] |
Definition at line 135 of file pointcloud2_plugin.h.
size_t mapviz_plugins::PointCloud2Plugin::buffer_size_ [private] |
Definition at line 139 of file pointcloud2_plugin.h.
QWidget* mapviz_plugins::PointCloud2Plugin::config_widget_ [private] |
Definition at line 132 of file pointcloud2_plugin.h.
bool mapviz_plugins::PointCloud2Plugin::has_message_ [private] |
Definition at line 141 of file pointcloud2_plugin.h.
std::vector<double> mapviz_plugins::PointCloud2Plugin::max_ [private] |
Definition at line 146 of file pointcloud2_plugin.h.
double mapviz_plugins::PointCloud2Plugin::max_value_ [private] |
Definition at line 136 of file pointcloud2_plugin.h.
std::vector<double> mapviz_plugins::PointCloud2Plugin::min_ [private] |
Definition at line 147 of file pointcloud2_plugin.h.
double mapviz_plugins::PointCloud2Plugin::min_value_ [private] |
Definition at line 137 of file pointcloud2_plugin.h.
bool mapviz_plugins::PointCloud2Plugin::need_minmax_ [private] |
Definition at line 145 of file pointcloud2_plugin.h.
bool mapviz_plugins::PointCloud2Plugin::need_new_list_ [private] |
Definition at line 143 of file pointcloud2_plugin.h.
bool mapviz_plugins::PointCloud2Plugin::new_topic_ [private] |
Definition at line 140 of file pointcloud2_plugin.h.
size_t mapviz_plugins::PointCloud2Plugin::num_of_feats_ [private] |
Definition at line 142 of file pointcloud2_plugin.h.
Definition at line 152 of file pointcloud2_plugin.h.
size_t mapviz_plugins::PointCloud2Plugin::point_size_ [private] |
Definition at line 138 of file pointcloud2_plugin.h.
std::string mapviz_plugins::PointCloud2Plugin::saved_color_transformer_ [private] |
Definition at line 144 of file pointcloud2_plugin.h.
QMutex mapviz_plugins::PointCloud2Plugin::scan_mutex_ [private] |
Definition at line 154 of file pointcloud2_plugin.h.
std::deque<Scan> mapviz_plugins::PointCloud2Plugin::scans_ [private] |
Definition at line 151 of file pointcloud2_plugin.h.
std::string mapviz_plugins::PointCloud2Plugin::topic_ [private] |
Definition at line 134 of file pointcloud2_plugin.h.
Ui::PointCloud2_config mapviz_plugins::PointCloud2Plugin::ui_ [private] |
Definition at line 131 of file pointcloud2_plugin.h.