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 ClearHistory();
00075
00076 void Draw(double x, double y, double scale);
00077
00078 void Transform();
00079
00080 void LoadConfig(const YAML::Node& node, const std::string& path);
00081 void SaveConfig(YAML::Emitter& emitter, const std::string& path);
00082
00083 QWidget* GetConfigWidget(QWidget* parent);
00084
00085 protected:
00086 void PrintError(const std::string& message);
00087 void PrintInfo(const std::string& message);
00088 void PrintWarning(const std::string& message);
00089
00090 protected Q_SLOTS:
00091 void SelectTopic();
00092 void TopicEdited();
00093 void AlphaEdited(double val);
00094 void ColorTransformerChanged(int index);
00095 void MinValueChanged(double value);
00096 void MaxValueChanged(double value);
00097 void PointSizeChanged(int value);
00098 void BufferSizeChanged(int value);
00099 void UseRainbowChanged(int check_state);
00100 void UpdateColors();
00101 void DrawIcon();
00102
00103 private:
00104 struct StampedPoint
00105 {
00106 tf::Point point;
00107 tf::Point transformed_point;
00108 QColor color;
00109 float range;
00110 float intensity;
00111 };
00112
00113 struct Scan
00114 {
00115 ros::Time stamp;
00116 QColor color;
00117 std::vector<StampedPoint> points;
00118 std::string source_frame_;
00119 bool transformed;
00120 bool has_intensity;
00121 };
00122
00123 void laserScanCallback(const sensor_msgs::LaserScanConstPtr& scan);
00124 QColor CalculateColor(const StampedPoint& point, bool has_intensity);
00125 void updatePreComputedTriginometic(const sensor_msgs::LaserScanConstPtr& msg);
00126
00127 Ui::laserscan_config ui_;
00128 QWidget* config_widget_;
00129
00130 std::string topic_;
00131 double alpha_;
00132 double min_value_;
00133 double max_value_;
00134 size_t point_size_;
00135 size_t buffer_size_;
00136
00137 bool has_message_;
00138
00139
00140
00141
00142 std::deque<Scan> scans_;
00143 ros::Subscriber laserscan_sub_;
00144 std::vector<double> precomputed_cos_;
00145 std::vector<double> precomputed_sin_;
00146 size_t prev_ranges_size_;
00147 float prev_angle_min_;
00148 float prev_increment_;
00149 };
00150 }
00151
00152 #endif // MAPVIZ_PLUGINS_LASERSCAN_PLUGIN_H_