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_DISPARITY_PLUGIN_H_
00031 #define MAPVIZ_PLUGINS_DISPARITY_PLUGIN_H_
00032
00033
00034 #include <mapviz/mapviz_plugin.h>
00035
00036
00037 #include <list>
00038 #include <string>
00039
00040
00041 #include <QColor>
00042 #include <QGLWidget>
00043 #include <QObject>
00044 #include <QWidget>
00045
00046
00047 #include <cv_bridge/cv_bridge.h>
00048 #include <opencv/highgui.h>
00049 #include <ros/ros.h>
00050 #include <stereo_msgs/DisparityImage.h>
00051 #include <tf/transform_datatypes.h>
00052
00053 #include <mapviz/map_canvas.h>
00054
00055
00056 #include "ui_disparity_config.h"
00057
00058 namespace mapviz_plugins
00059 {
00060 class DisparityPlugin : 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 enum Units {PIXELS, PERCENT};
00077
00078 DisparityPlugin();
00079 virtual ~DisparityPlugin();
00080
00081 bool Initialize(QGLWidget* canvas);
00082 void Shutdown() {}
00083
00084 void Draw(double x, double y, double scale);
00085
00086 void Transform() {}
00087
00088 void LoadConfig(const YAML::Node& node, const std::string& path);
00089 void SaveConfig(YAML::Emitter& emitter, const std::string& path);
00090
00091 QWidget* GetConfigWidget(QWidget* parent);
00092
00093 protected:
00094 void PrintError(const std::string& message);
00095 void PrintInfo(const std::string& message);
00096 void PrintWarning(const std::string& message);
00097
00098 protected Q_SLOTS:
00099 void SelectTopic();
00100 void TopicEdited();
00101 void SetAnchor(QString anchor);
00102 void SetUnits(QString units);
00103 void SetOffsetX(int offset);
00104 void SetOffsetY(int offset);
00105 void SetWidth(int width);
00106 void SetHeight(int height);
00107 void SetSubscription(bool visible);
00108
00109 private:
00110 Ui::disparity_config ui_;
00111 QWidget* config_widget_;
00112
00113 std::string topic_;
00114 Anchor anchor_;
00115 Units units_;
00116 double offset_x_;
00117 double offset_y_;
00118 double width_;
00119 double height_;
00120
00121 bool has_image_;
00122
00123 double last_width_;
00124 double last_height_;
00125
00126 ros::Subscriber disparity_sub_;
00127 bool has_message_;
00128
00129 stereo_msgs::DisparityImage disparity_;
00130
00131 cv::Mat_<cv::Vec3b> disparity_color_;
00132 cv::Mat scaled_image_;
00133
00134 void disparityCallback(const stereo_msgs::DisparityImageConstPtr& image);
00135
00136 void ScaleImage(double width, double height);
00137 void DrawIplImage(cv::Mat *image);
00138
00139 std::string AnchorToString(Anchor anchor);
00140 std::string UnitsToString(Units units);
00141
00142 const static unsigned char COLOR_MAP[];
00143 };
00144 }
00145
00146 #endif // MAPVIZ_PLUGINS_DISPARITY_PLUGIN_H_