map_canvas.h
Go to the documentation of this file.
00001 // *****************************************************************************
00002 //
00003 // Copyright (c) 2014, Southwest Research Institute® (SwRI®)
00004 // All rights reserved.
00005 //
00006 // Redistribution and use in source and binary forms, with or without
00007 // modification, are permitted provided that the following conditions are met:
00008 //     * Redistributions of source code must retain the above copyright
00009 //       notice, this list of conditions and the following disclaimer.
00010 //     * Redistributions in binary form must reproduce the above copyright
00011 //       notice, this list of conditions and the following disclaimer in the
00012 //       documentation and/or other materials provided with the distribution.
00013 //     * Neither the name of Southwest Research Institute® (SwRI®) nor the
00014 //       names of its contributors may be used to endorse or promote products
00015 //       derived from this software without specific prior written permission.
00016 //
00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020 // ARE DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT HOLDER> BE LIABLE FOR ANY
00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00027 //
00028 // *****************************************************************************
00029 
00030 #ifndef MAPVIZ_MAP_CANVAS_H_
00031 #define MAPVIZ_MAP_CANVAS_H_
00032 
00033 // C++ standard libraries
00034 #include <cstring>
00035 #include <list>
00036 #include <string>
00037 #include <vector>
00038 
00039 #include <boost/shared_ptr.hpp>
00040 
00041 #include <GL/glew.h>
00042 #include <GL/gl.h>
00043 
00044 // QT libraries
00045 #include <QGLWidget>
00046 #include <QMouseEvent>
00047 #include <QWheelEvent>
00048 #include <QColor>
00049 #include <QTimer>
00050 
00051 // ROS libraries
00052 #include <ros/ros.h>
00053 #include <tf/transform_datatypes.h>
00054 #include <tf/transform_listener.h>
00055 
00056 #include <mapviz/mapviz_plugin.h>
00057 
00058 namespace mapviz
00059 {
00060   class MapCanvas : public QGLWidget
00061   {
00062     Q_OBJECT
00063 
00064   public:
00065     explicit MapCanvas(QWidget *parent = 0);
00066     ~MapCanvas();
00067 
00068     void InitializeTf(boost::shared_ptr<tf::TransformListener> tf);
00069 
00070     void AddPlugin(MapvizPluginPtr plugin, int order);
00071     void RemovePlugin(MapvizPluginPtr plugin);
00072     void SetFixedFrame(const std::string& frame);
00073     void SetTargetFrame(const std::string& frame);
00074     void ToggleFixOrientation(bool on);
00075     void ToggleRotate90(bool on);
00076     void ToggleEnableAntialiasing(bool on);
00077     void ToggleUseLatestTransforms(bool on);
00078     void UpdateView();
00079     void ReorderDisplays();
00080     void ResetLocation();
00081     QPointF MapGlCoordToFixedFrame(const QPointF& point);
00082     QPointF FixedFrameToMapGlCoord(const QPointF& point);
00083 
00084     double frameRate() const;
00085 
00086     float ViewScale() const { return view_scale_; }
00087     float OffsetX() const { return offset_x_; }
00088     float OffsetY() const { return offset_y_; }
00089 
00090     void SetViewScale(float scale)
00091     {
00092       view_scale_ = scale;
00093       UpdateView();
00094     }
00095 
00096     void SetOffsetX(float x)
00097     {
00098       offset_x_ = x;
00099       UpdateView();
00100     }
00101 
00102     void SetOffsetY(float y)
00103     {
00104       offset_y_ = y;
00105       UpdateView();
00106     }
00107 
00108     void SetBackground(const QColor& color)
00109     {
00110       bg_color_ = color;
00111       update();
00112     }
00113 
00114     void CaptureFrames(bool enabled)
00115     {
00116       capture_frames_ = enabled;
00117       update();
00118     }
00119 
00127     bool CopyCaptureBuffer(uchar* buffer)
00128     {
00129       if (!capture_buffer_.empty())
00130       {
00131         memcpy(&buffer[0], &capture_buffer_[0], capture_buffer_.size());
00132         return true;
00133       }
00134 
00135       return false;
00136     }
00137 
00144     bool CopyCaptureBuffer(std::vector<uint8_t>& buffer)
00145     {
00146       buffer.clear();
00147       if (!capture_buffer_.empty())
00148       {
00149         buffer.resize(capture_buffer_.size());
00150         memcpy(&buffer[0], &capture_buffer_[0], buffer.size());
00151 
00152         return true;
00153       }
00154 
00155       return false;
00156     }
00157 
00158     void CaptureFrame(bool force = false);
00159 
00160   Q_SIGNALS:
00161     void Hover(double x, double y, double scale);
00162 
00163   public Q_SLOTS:
00164     void setFrameRate(const double fps);
00165 
00166   protected:
00167     void initializeGL();
00168     void initGlBlending();
00169     void pushGlMatrices();
00170     void popGlMatrices();
00171     void resizeGL(int w, int h);
00172     void paintEvent(QPaintEvent* event);
00173     void wheelEvent(QWheelEvent* e);
00174     void mousePressEvent(QMouseEvent* e);
00175     void mouseReleaseEvent(QMouseEvent* e);
00176     void mouseMoveEvent(QMouseEvent* e);
00177     void leaveEvent(QEvent* e);
00178 
00179     void Recenter();
00180     void TransformTarget(QPainter* painter);
00181     void Zoom(float factor);
00182 
00183     void InitializePixelBuffers();
00184 
00185     bool has_pixel_buffers_;
00186     int32_t pixel_buffer_size_;
00187     GLuint pixel_buffer_ids_[2];
00188     int32_t pixel_buffer_index_;
00189     bool capture_frames_;
00190 
00191     bool initialized_;
00192     bool fix_orientation_;
00193     bool rotate_90_;
00194     bool enable_antialiasing_;
00195 
00196     QTimer frame_rate_timer_;
00197 
00198     QColor bg_color_;
00199 
00200     Qt::MouseButton mouse_button_;
00201     bool mouse_pressed_;
00202     int mouse_x_;
00203     int mouse_y_;
00204     // Used when right-click dragging to zoom
00205     int mouse_previous_y_;
00206 
00207     bool mouse_hovering_;
00208     int mouse_hover_x_;
00209     int mouse_hover_y_;
00210 
00211     // Offset based on previous mouse drags
00212     double offset_x_;
00213     double offset_y_;
00214 
00215     // Offset based on current mouse drag
00216     double drag_x_;
00217     double drag_y_;
00218 
00219     // The center of the view
00220     float view_center_x_;
00221     float view_center_y_;
00222 
00223     // View scale in meters per pixel
00224     float view_scale_;
00225 
00226     // The bounds of the view
00227     float view_left_;
00228     float view_right_;
00229     float view_top_;
00230     float view_bottom_;
00231 
00232     // The bounds of the scene
00233     float scene_left_;
00234     float scene_right_;
00235     float scene_top_;
00236     float scene_bottom_;
00237 
00238     std::string fixed_frame_;
00239     std::string target_frame_;
00240 
00241     boost::shared_ptr<tf::TransformListener> tf_;
00242     tf::StampedTransform transform_;
00243     QTransform qtransform_;
00244     std::list<MapvizPluginPtr> plugins_;
00245 
00246     std::vector<uint8_t> capture_buffer_;
00247   };
00248 }
00249 
00250 #endif  // MAPVIZ_MAP_CANVAS_H_


mapviz
Author(s): Marc Alban
autogenerated on Thu Aug 24 2017 02:45:59