Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #ifndef MAPVIZ_PLUGINS_LASERSCAN_PLUGIN_H_
00031 #define MAPVIZ_PLUGINS_LASERSCAN_PLUGIN_H_
00032
00033
00034 #include <string>
00035 #include <deque>
00036 #include <vector>
00037
00038 #include <mapviz/mapviz_plugin.h>
00039
00040
00041 #include <QGLWidget>
00042 #include <QColor>
00043
00044
00045 #include <sensor_msgs/LaserScan.h>
00046
00047
00048 #include "ui_laserscan_config.h"
00049
00050 namespace mapviz_plugins
00051 {
00052 class LaserScanPlugin : public mapviz::MapvizPlugin
00053 {
00054 Q_OBJECT
00055
00056 public:
00057 enum
00058 {
00059 COLOR_FLAT = 0,
00060 COLOR_INTENSITY = 1,
00061 COLOR_RANGE = 2,
00062 COLOR_X = 3,
00063 COLOR_Y = 4,
00064 COLOR_Z = 5
00065 };
00066 LaserScanPlugin();
00067 virtual ~LaserScanPlugin();
00068
00069 bool Initialize(QGLWidget* canvas);
00070 void Shutdown()
00071 {
00072 }
00073
00074 void Draw(double x, double y, double scale);
00075
00076 void Transform();
00077
00078 void LoadConfig(const YAML::Node& node, const std::string& path);
00079 void SaveConfig(YAML::Emitter& emitter, const std::string& path);
00080
00081 QWidget* GetConfigWidget(QWidget* parent);
00082
00083 protected:
00084 void PrintError(const std::string& message);
00085 void PrintInfo(const std::string& message);
00086 void PrintWarning(const std::string& message);
00087
00088 protected Q_SLOTS:
00089 void SelectTopic();
00090 void TopicEdited();
00091 void AlphaEdited();
00092 void ColorTransformerChanged(int index);
00093 void MinValueChanged(double value);
00094 void MaxValueChanged(double value);
00095 void PointSizeChanged(int value);
00096 void BufferSizeChanged(int value);
00097 void UseRainbowChanged(int check_state);
00098 void UpdateColors();
00099 void DrawIcon();
00100
00101 private:
00102 struct StampedPoint
00103 {
00104 tf::Point point;
00105 tf::Point transformed_point;
00106 QColor color;
00107 float range;
00108 float intensity;
00109 };
00110
00111 struct Scan
00112 {
00113 ros::Time stamp;
00114 QColor color;
00115 std::vector<StampedPoint> points;
00116 std::string source_frame_;
00117 bool transformed;
00118 bool has_intensity;
00119 };
00120
00121 void laserScanCallback(const sensor_msgs::LaserScanConstPtr& scan);
00122 QColor CalculateColor(const StampedPoint& point, bool has_intensity);
00123
00124 Ui::laserscan_config ui_;
00125 QWidget* config_widget_;
00126
00127 std::string topic_;
00128 double alpha_;
00129 double min_value_;
00130 double max_value_;
00131 size_t point_size_;
00132 size_t buffer_size_;
00133
00134 bool has_message_;
00135
00136
00137
00138
00139 std::deque<Scan> scans_;
00140 ros::Subscriber laserscan_sub_;
00141 };
00142 }
00143
00144 #endif // MAPVIZ_PLUGINS_LASERSCAN_PLUGIN_H_