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