00001 /* 00002 * Copyright (c) 2011, Dirk Thomas, TU Darmstadt 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions 00007 * are met: 00008 * 00009 * * Redistributions of source code must retain the above copyright 00010 * notice, this list of conditions and the following disclaimer. 00011 * * Redistributions in binary form must reproduce the above 00012 * copyright notice, this list of conditions and the following 00013 * disclaimer in the documentation and/or other materials provided 00014 * with the distribution. 00015 * * Neither the name of the TU Darmstadt nor the names of its 00016 * contributors may be used to endorse or promote products derived 00017 * from this software without specific prior written permission. 00018 * 00019 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00020 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00021 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00022 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00023 * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00024 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00025 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00026 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00027 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00028 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00029 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00030 * POSSIBILITY OF SUCH DAMAGE. 00031 */ 00032 00033 #ifndef rqt_map_merger__MapMerger_H 00034 #define rqt_map_merger__MapMerger_H 00035 00036 #include <rqt_gui_cpp/plugin.h> 00037 00038 #include <ui_map_merger.h> 00039 00040 #include <image_transport/image_transport.h> 00041 #include <sensor_msgs/Image.h> 00042 #include <nav_msgs/OccupancyGrid.h> 00043 00044 00045 #include <opencv2/core/core.hpp> 00046 00047 #include <QImage> 00048 #include <QList> 00049 #include <QMutex> 00050 #include <QString> 00051 #include <QSize> 00052 #include <QWidget> 00053 00054 #include <vector> 00055 00056 00057 namespace rqt_map_merger { 00058 00059 class MapMerger 00060 : public rqt_gui_cpp::Plugin 00061 { 00062 00063 Q_OBJECT 00064 00065 public: 00066 00067 MapMerger(); 00068 00069 virtual void initPlugin(qt_gui_cpp::PluginContext& context); 00070 cv::Mat occupancyGridToCvMat(const nav_msgs::OccupancyGrid * map); 00071 nav_msgs::OccupancyGrid cvMatToOccupancyGrid(const cv::Mat * im); 00072 00073 virtual void shutdownPlugin(); 00074 bool eventFilter(QObject* watched, QEvent* event); 00075 00076 void redraw_Label_1(); 00077 void redraw_Label_2(); 00078 void redraw_Label_merged(); 00079 void timerCallback(const ros::TimerEvent& e); 00080 00081 00082 public slots: 00083 void onSlider1Moved(int idx); 00084 void onSlider2Moved(int idx); 00085 void onMergePressed(); 00086 void onSaveGeotiffPressed(); 00087 void onStateUseTransformChanged(int checked); 00088 void onGetTransform(); 00089 00090 00091 protected: 00092 00093 void map1Callback(nav_msgs::OccupancyGridConstPtr const & map); 00094 void map2Callback(nav_msgs::OccupancyGridConstPtr const & map); 00095 00096 protected slots: 00097 00098 00099 protected: 00100 00101 00102 00103 Ui::MapMergerWidget ui_; 00104 00105 QWidget* widget_; 00106 00107 image_transport::Subscriber subscriber_; 00108 00109 ros::Subscriber map_1_sub_; 00110 ros::Subscriber map_2_sub_; 00111 00112 std::vector<QImage> qimages_1_; 00113 std::vector<cv::Mat> cv_maps_1_; 00114 std::vector<nav_msgs::OccupancyGrid> og_maps_1_; 00115 QImage qimage_1_; 00116 cv::Mat cv_map_1_; 00117 nav_msgs::OccupancyGrid og_map_1_; 00118 std::vector<QImage> qimages_2_; 00119 std::vector<cv::Mat> cv_maps_2_; 00120 std::vector<nav_msgs::OccupancyGrid> og_maps_2_; 00121 QImage qimage_2_; 00122 cv::Mat cv_map_2_; 00123 nav_msgs::OccupancyGrid og_map_2_; 00124 00125 QImage qimage_merged_; 00126 QMutex qimage_mutex_; 00127 00128 cv::Mat conversion_mat_; 00129 cv::Mat stored_transform; 00130 cv::Mat current_transform; 00131 00132 ros::NodeHandle my_nh_; 00133 00134 int current_idx_1_; 00135 int current_idx_2_; 00136 00137 int stored_idx_1_; 00138 int stored_idx_2_; 00139 00140 bool use_stored_transform_; 00141 int first_map_1_received; 00142 int first_map_2_received; 00143 00144 ros::Timer map_save_timer_; 00145 00146 ros::Publisher map_1_to_use_pub_; 00147 ros::Publisher map_2_to_use_pub_; 00148 ros::Publisher hector_command_pub_; 00149 00150 }; 00151 00152 } 00153 00154 #endif // rqt_image_view__ImageView_H