#include <laserscan_plugin.h>

Classes | |
| struct | Scan |
| struct | StampedPoint |
Public Types | |
| enum | { COLOR_FLAT = 0, COLOR_INTENSITY = 1, COLOR_RANGE = 2, COLOR_X = 3, COLOR_Y = 4, COLOR_Z = 5 } |
Public Member Functions | |
| void | Draw (double x, double y, double scale) |
| QWidget * | GetConfigWidget (QWidget *parent) |
| bool | Initialize (QGLWidget *canvas) |
| LaserScanPlugin () | |
| void | LoadConfig (const YAML::Node &node, const std::string &path) |
| void | SaveConfig (YAML::Emitter &emitter, const std::string &path) |
| void | Shutdown () |
| void | Transform () |
| virtual | ~LaserScanPlugin () |
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 | SelectTopic () |
| void | TopicEdited () |
| void | UpdateColors () |
| 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, bool has_intensity) |
| void | laserScanCallback (const sensor_msgs::LaserScanConstPtr &scan) |
Private Attributes | |
| double | alpha_ |
| size_t | buffer_size_ |
| QWidget * | config_widget_ |
| bool | has_message_ |
| ros::Subscriber | laserscan_sub_ |
| double | max_value_ |
| double | min_value_ |
| size_t | point_size_ |
| std::deque< Scan > | scans_ |
| std::string | topic_ |
| Ui::laserscan_config | ui_ |
Definition at line 52 of file laserscan_plugin.h.
| anonymous enum |
Definition at line 57 of file laserscan_plugin.h.
| virtual mapviz_plugins::LaserScanPlugin::~LaserScanPlugin | ( | ) | [virtual] |
| void mapviz_plugins::LaserScanPlugin::AlphaEdited | ( | ) | [protected, slot] |
| void mapviz_plugins::LaserScanPlugin::BufferSizeChanged | ( | int | value | ) | [protected, slot] |
| QColor mapviz_plugins::LaserScanPlugin::CalculateColor | ( | const StampedPoint & | point, |
| bool | has_intensity | ||
| ) | [private] |
| void mapviz_plugins::LaserScanPlugin::ColorTransformerChanged | ( | int | index | ) | [protected, slot] |
| void mapviz_plugins::LaserScanPlugin::Draw | ( | double | x, |
| double | y, | ||
| double | scale | ||
| ) | [virtual] |
Implements mapviz::MapvizPlugin.
| void mapviz_plugins::LaserScanPlugin::DrawIcon | ( | ) | [protected, virtual, slot] |
Reimplemented from mapviz::MapvizPlugin.
| QWidget* mapviz_plugins::LaserScanPlugin::GetConfigWidget | ( | QWidget * | parent | ) | [virtual] |
Reimplemented from mapviz::MapvizPlugin.
| bool mapviz_plugins::LaserScanPlugin::Initialize | ( | QGLWidget * | canvas | ) | [virtual] |
Implements mapviz::MapvizPlugin.
| void mapviz_plugins::LaserScanPlugin::laserScanCallback | ( | const sensor_msgs::LaserScanConstPtr & | scan | ) | [private] |
| void mapviz_plugins::LaserScanPlugin::LoadConfig | ( | const YAML::Node & | node, |
| const std::string & | path | ||
| ) | [virtual] |
Implements mapviz::MapvizPlugin.
| void mapviz_plugins::LaserScanPlugin::MaxValueChanged | ( | double | value | ) | [protected, slot] |
| void mapviz_plugins::LaserScanPlugin::MinValueChanged | ( | double | value | ) | [protected, slot] |
| void mapviz_plugins::LaserScanPlugin::PointSizeChanged | ( | int | value | ) | [protected, slot] |
| void mapviz_plugins::LaserScanPlugin::PrintError | ( | const std::string & | message | ) | [protected, virtual] |
Implements mapviz::MapvizPlugin.
| void mapviz_plugins::LaserScanPlugin::PrintInfo | ( | const std::string & | message | ) | [protected, virtual] |
Implements mapviz::MapvizPlugin.
| void mapviz_plugins::LaserScanPlugin::PrintWarning | ( | const std::string & | message | ) | [protected, virtual] |
Implements mapviz::MapvizPlugin.
| void mapviz_plugins::LaserScanPlugin::SaveConfig | ( | YAML::Emitter & | emitter, |
| const std::string & | path | ||
| ) | [virtual] |
Implements mapviz::MapvizPlugin.
| void mapviz_plugins::LaserScanPlugin::SelectTopic | ( | ) | [protected, slot] |
| void mapviz_plugins::LaserScanPlugin::Shutdown | ( | ) | [inline, virtual] |
Implements mapviz::MapvizPlugin.
Definition at line 70 of file laserscan_plugin.h.
| void mapviz_plugins::LaserScanPlugin::TopicEdited | ( | ) | [protected, slot] |
| void mapviz_plugins::LaserScanPlugin::Transform | ( | ) | [virtual] |
Implements mapviz::MapvizPlugin.
| void mapviz_plugins::LaserScanPlugin::UpdateColors | ( | ) | [protected, slot] |
| void mapviz_plugins::LaserScanPlugin::UseRainbowChanged | ( | int | check_state | ) | [protected, slot] |
double mapviz_plugins::LaserScanPlugin::alpha_ [private] |
Definition at line 128 of file laserscan_plugin.h.
size_t mapviz_plugins::LaserScanPlugin::buffer_size_ [private] |
Definition at line 132 of file laserscan_plugin.h.
QWidget* mapviz_plugins::LaserScanPlugin::config_widget_ [private] |
Definition at line 125 of file laserscan_plugin.h.
bool mapviz_plugins::LaserScanPlugin::has_message_ [private] |
Definition at line 134 of file laserscan_plugin.h.
Definition at line 140 of file laserscan_plugin.h.
double mapviz_plugins::LaserScanPlugin::max_value_ [private] |
Definition at line 130 of file laserscan_plugin.h.
double mapviz_plugins::LaserScanPlugin::min_value_ [private] |
Definition at line 129 of file laserscan_plugin.h.
size_t mapviz_plugins::LaserScanPlugin::point_size_ [private] |
Definition at line 131 of file laserscan_plugin.h.
std::deque<Scan> mapviz_plugins::LaserScanPlugin::scans_ [private] |
Definition at line 139 of file laserscan_plugin.h.
std::string mapviz_plugins::LaserScanPlugin::topic_ [private] |
Definition at line 127 of file laserscan_plugin.h.
Ui::laserscan_config mapviz_plugins::LaserScanPlugin::ui_ [private] |
Definition at line 124 of file laserscan_plugin.h.