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_MARKER_PLUGIN_H_
00031 #define MAPVIZ_PLUGINS_MARKER_PLUGIN_H_
00032
00033
00034 #include <string>
00035 #include <list>
00036 #include <map>
00037
00038 #include <mapviz/mapviz_plugin.h>
00039
00040
00041 #include <QGLWidget>
00042 #include <QObject>
00043 #include <QWidget>
00044 #include <QColor>
00045
00046
00047 #include <ros/ros.h>
00048 #include <tf/transform_datatypes.h>
00049 #include <topic_tools/shape_shifter.h>
00050 #include <visualization_msgs/Marker.h>
00051 #include <visualization_msgs/MarkerArray.h>
00052 #include <std_msgs/ColorRGBA.h>
00053
00054 #include <mapviz/map_canvas.h>
00055
00056
00057 #include "ui_marker_config.h"
00058
00059 namespace mapviz_plugins
00060 {
00061 class MarkerPlugin : public mapviz::MapvizPlugin
00062 {
00063 Q_OBJECT
00064
00065 public:
00066 MarkerPlugin();
00067 virtual ~MarkerPlugin();
00068
00069 bool Initialize(QGLWidget* canvas);
00070 void Shutdown() {}
00071
00072 void ClearHistory();
00073
00074 void Draw(double x, double y, double scale);
00075 void Paint(QPainter* painter, double x, double y, double scale);
00076
00077 void Transform();
00078
00079 void LoadConfig(const YAML::Node& node, const std::string& path);
00080 void SaveConfig(YAML::Emitter& emitter, const std::string& path);
00081
00082 QWidget* GetConfigWidget(QWidget* parent);
00083
00084 bool SupportsPainting()
00085 {
00086 return true;
00087 }
00088
00089 protected:
00090 void PrintError(const std::string& message);
00091 void PrintInfo(const std::string& message);
00092 void PrintWarning(const std::string& message);
00093 void timerEvent(QTimerEvent *);
00094
00095 protected Q_SLOTS:
00096 void SelectTopic();
00097 void TopicEdited();
00098
00099 private:
00100 struct StampedPoint
00101 {
00102 tf::Point point;
00103 tf::Quaternion orientation;
00104
00105 tf::Point transformed_point;
00106
00107 tf::Point arrow_point;
00108 tf::Point transformed_arrow_point;
00109 tf::Point transformed_arrow_left;
00110 tf::Point transformed_arrow_right;
00111
00112 QColor color;
00113 };
00114
00115 struct MarkerData
00116 {
00117 ros::Time stamp;
00118 ros::Time expire_time;
00119
00120 int display_type;
00121 QColor color;
00122
00123 std::list<StampedPoint> points;
00124 std::string text;
00125
00126 float scale_x;
00127 float scale_y;
00128 float scale_z;
00129
00130 std::string source_frame;
00131 swri_transform_util::Transform local_transform;
00132
00133 bool transformed;
00134 };
00135
00136 Ui::marker_config ui_;
00137 QWidget* config_widget_;
00138
00139 std::string topic_;
00140
00141 ros::Subscriber marker_sub_;
00142 bool connected_;
00143 bool has_message_;
00144
00145 std::map<std::string, std::map<int, MarkerData> > markers_;
00146
00147 void handleMessage(const topic_tools::ShapeShifter::ConstPtr& msg);
00148 void handleMarker(const visualization_msgs::Marker &marker);
00149 void handleMarkerArray(const visualization_msgs::MarkerArray &markers);
00150 void transformArrow(MarkerData& markerData,
00151 const swri_transform_util::Transform& transform);
00152 };
00153 }
00154
00155 #endif // MAPVIZ_PLUGINS_MARKER_PLUGIN_H_