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
00031 #ifndef MAPVIZ_PLUGINS_STRING_PLUGIN_H
00032 #define MAPVIZ_PLUGINS_STRING_PLUGIN_H
00033
00034 #include <string>
00035
00036 #include <mapviz/mapviz_plugin.h>
00037
00038 #include <QObject>
00039 #include <QString>
00040 #include <QColor>
00041 #include <QWidget>
00042 #include <QGLWidget>
00043 #include <QPainter>
00044 #include <QFont>
00045 #include <QStaticText>
00046
00047
00048 #include <ros/ros.h>
00049 #include <std_msgs/String.h>
00050
00051
00052 #include "ui_string_config.h"
00053
00054 namespace mapviz_plugins
00055 {
00056 class StringPlugin : public mapviz::MapvizPlugin
00057 {
00058 Q_OBJECT
00059
00060 public:
00061 enum Anchor {
00062 TOP_LEFT,
00063 TOP_CENTER,
00064 TOP_RIGHT,
00065 CENTER_LEFT,
00066 CENTER,
00067 CENTER_RIGHT,
00068 BOTTOM_LEFT,
00069 BOTTOM_CENTER,
00070 BOTTOM_RIGHT
00071 };
00072
00073 enum Units {
00074 PIXELS,
00075 PERCENT
00076 };
00077
00078 StringPlugin();
00079 virtual ~StringPlugin();
00080
00081 bool Initialize(QGLWidget* canvas);
00082 void Shutdown() {}
00083
00084 void Draw(double x, double y, double scale);
00085 void Paint(QPainter* painter, double x, double y, double scale);
00086
00087 void Transform() {}
00088
00089 void LoadConfig(const YAML::Node& node, const std::string& path);
00090 void SaveConfig(YAML::Emitter& emitter, const std::string& path);
00091
00092 QWidget* GetConfigWidget(QWidget* parent);
00093
00094 bool SupportsPainting()
00095 {
00096 return true;
00097 }
00098
00099 protected:
00100 void PaintText(QPainter* painter);
00101 void PrintError(const std::string& message);
00102 void PrintInfo(const std::string& message);
00103 void PrintWarning(const std::string& message);
00104
00105 protected Q_SLOTS:
00106 void SelectColor();
00107 void SelectFont();
00108 void SelectTopic();
00109 void TopicEdited();
00110 void SetAnchor(QString anchor);
00111 void SetUnits(QString units);
00112 void SetOffsetX(int offset);
00113 void SetOffsetY(int offset);
00114
00115 private:
00116 Ui::string_config ui_;
00117 QWidget* config_widget_;
00118
00119 std::string topic_;
00120 Anchor anchor_;
00121 Units units_;
00122 int offset_x_;
00123 int offset_y_;
00124
00125 ros::Subscriber string_sub_;
00126 bool has_message_;
00127 bool has_painted_;
00128
00129 QColor color_;
00130 QFont font_;
00131 QStaticText message_;
00132
00133 void stringCallback(const std_msgs::StringConstPtr& str);
00134
00135 std::string AnchorToString(Anchor anchor);
00136 std::string UnitsToString(Units units);
00137
00138 static const char* ANCHOR_KEY;
00139 static const char* COLOR_KEY;
00140 static const char* FONT_KEY;
00141 static const char* OFFSET_X_KEY;
00142 static const char* OFFSET_Y_KEY;
00143 static const char* TOPIC_KEY;
00144 static const char* UNITS_KEY;
00145 };
00146 }
00147
00148
00149 #endif //MAPVIZ_PLUGINS_STRING_PLUGIN_H