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_IMAGE_PLUGIN_H_
00031 #define MAPVIZ_PLUGINS_IMAGE_PLUGIN_H_
00032
00033
00034 #include <string>
00035 #include <list>
00036
00037 #include <mapviz/mapviz_plugin.h>
00038
00039
00040 #include <QGLWidget>
00041 #include <QObject>
00042 #include <QWidget>
00043 #include <QColor>
00044
00045
00046 #include <ros/ros.h>
00047 #include <tf/transform_datatypes.h>
00048 #include <sensor_msgs/Image.h>
00049 #include <opencv/highgui.h>
00050 #include <cv_bridge/cv_bridge.h>
00051 #include <image_transport/image_transport.h>
00052
00053 #include <mapviz/map_canvas.h>
00054
00055
00056 #include "ui_image_config.h"
00057
00058 namespace mapviz_plugins
00059 {
00060 class ImagePlugin : public mapviz::MapvizPlugin
00061 {
00062 Q_OBJECT
00063
00064 public:
00065 enum Anchor {
00066 TOP_LEFT,
00067 TOP_CENTER,
00068 TOP_RIGHT,
00069 CENTER_LEFT,
00070 CENTER,
00071 CENTER_RIGHT,
00072 BOTTOM_LEFT,
00073 BOTTOM_CENTER,
00074 BOTTOM_RIGHT
00075 };
00076
00077 enum Units {PIXELS, PERCENT};
00078
00079 ImagePlugin();
00080 virtual ~ImagePlugin();
00081
00082 bool Initialize(QGLWidget* canvas);
00083 void Shutdown() {}
00084
00085 void Draw(double x, double y, double scale);
00086
00087 void CreateLocalNode();
00088 virtual void SetNode(const ros::NodeHandle& node);
00089
00090 void Transform() {}
00091
00092 void LoadConfig(const YAML::Node& node, const std::string& path);
00093 void SaveConfig(YAML::Emitter& emitter, const std::string& path);
00094
00095 QWidget* GetConfigWidget(QWidget* parent);
00096
00097 protected:
00098 void PrintError(const std::string& message);
00099 void PrintInfo(const std::string& message);
00100 void PrintWarning(const std::string& message);
00101
00102 public Q_SLOTS:
00103 void Resubscribe();
00104
00105 protected Q_SLOTS:
00106 void SelectTopic();
00107 void TopicEdited();
00108 void SetAnchor(QString anchor);
00109 void SetUnits(QString units);
00110 void SetOffsetX(int offset);
00111 void SetOffsetY(int offset);
00112 void SetWidth(double width);
00113 void SetHeight(double height);
00114 void SetSubscription(bool visible);
00115 void SetTransport(const QString& transport);
00116 void KeepRatioChanged(bool checked);
00117
00118 private:
00119 Ui::image_config ui_;
00120 QWidget* config_widget_;
00121
00122 std::string topic_;
00123 Anchor anchor_;
00124 Units units_;
00125 int offset_x_;
00126 int offset_y_;
00127 double width_;
00128 double height_;
00129 QString transport_;
00130
00131 bool force_resubscribe_;
00132 bool has_image_;
00133
00134 double last_width_;
00135 double last_height_;
00136 double original_aspect_ratio_;
00137
00138 ros::NodeHandle local_node_;
00139 image_transport::Subscriber image_sub_;
00140 bool has_message_;
00141
00142 sensor_msgs::Image image_;
00143
00144 cv_bridge::CvImagePtr cv_image_;
00145 cv::Mat scaled_image_;
00146
00147 void imageCallback(const sensor_msgs::ImageConstPtr& image);
00148
00149 void ScaleImage(double width, double height);
00150 void DrawIplImage(cv::Mat *image);
00151
00152 std::string AnchorToString(Anchor anchor);
00153 std::string UnitsToString(Units units);
00154 };
00155 }
00156
00157 #endif // MAPVIZ_PLUGINS_IMAGE_PLUGIN_H_