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 // QT libraries
00042 #include <QGLWidget>
00043 #include <QMouseEvent>
00044 #include <QWheelEvent>
00045 #include <QColor>
00046 #include <QTimer>
00047 
00048 // ROS libraries
00049 #include <ros/ros.h>
00050 #include <tf/transform_datatypes.h>
00051 #include <tf/transform_listener.h>
00052 
00053 #include <mapviz/mapviz_plugin.h>
00054 
00055 namespace mapviz
00056 {
00057   class MapCanvas : public QGLWidget
00058   {
00059     Q_OBJECT
00060 
00061   public:
00062     explicit MapCanvas(QWidget *parent = 0);
00063     ~MapCanvas();
00064 
00065     void InitializeTf(boost::shared_ptr<tf::TransformListener> tf);
00066 
00067     void AddPlugin(MapvizPluginPtr plugin, int order);
00068     void RemovePlugin(MapvizPluginPtr plugin);
00069     void SetFixedFrame(const std::string& frame);
00070     void SetTargetFrame(const std::string& frame);
00071     void ToggleFixOrientation(bool on);
00072     void ToggleRotate90(bool on);
00073     void ToggleEnableAntialiasing(bool on);
00074     void ToggleUseLatestTransforms(bool on);
00075     void UpdateView();
00076     void ReorderDisplays();
00077     void ResetLocation();
00078     QPointF MapGlCoordToFixedFrame(const QPointF& point);
00079     QPointF FixedFrameToMapGlCoord(const QPointF& point);
00080 
00081     double frameRate() const;
00082 
00083     float ViewScale() const { return view_scale_; }
00084     float OffsetX() const { return offset_x_; }
00085     float OffsetY() const { return offset_y_; }
00086 
00087     void SetViewScale(float scale)
00088     {
00089       view_scale_ = scale;
00090       UpdateView();
00091     }
00092 
00093     void SetOffsetX(float x)
00094     {
00095       offset_x_ = x;
00096       UpdateView();
00097     }
00098 
00099     void SetOffsetY(float y)
00100     {
00101       offset_y_ = y;
00102       UpdateView();
00103     }
00104 
00105     void SetBackground(const QColor& color)
00106     {
00107       bg_color_ = color;
00108       update();
00109     }
00110 
00111     void CaptureFrames(bool enabled)
00112     {
00113       capture_frames_ = enabled;
00114       update();
00115     }
00116 
00124     bool CopyCaptureBuffer(uchar* buffer)
00125     {
00126       if (!capture_buffer_.empty())
00127       {
00128         memcpy(&buffer[0], &capture_buffer_[0], capture_buffer_.size());
00129         return true;
00130       }
00131 
00132       return false;
00133     }
00134 
00141     bool CopyCaptureBuffer(std::vector<uint8_t>& buffer)
00142     {
00143       buffer.clear();
00144       if (!capture_buffer_.empty())
00145       {
00146         buffer.resize(capture_buffer_.size());
00147         memcpy(&buffer[0], &capture_buffer_[0], buffer.size());
00148 
00149         return true;
00150       }
00151 
00152       return false;
00153     }
00154 
00155     void CaptureFrame(bool force = false);
00156 
00157   Q_SIGNALS:
00158     void Hover(double x, double y, double scale);
00159 
00160   public Q_SLOTS:
00161     void setFrameRate(const double fps);
00162 
00163   protected:
00164     void initializeGL();
00165     void initGlBlending();
00166     void pushGlMatrices();
00167     void popGlMatrices();
00168     void resizeGL(int w, int h);
00169     void paintEvent(QPaintEvent* event);
00170     void wheelEvent(QWheelEvent* e);
00171     void mousePressEvent(QMouseEvent* e);
00172     void mouseReleaseEvent(QMouseEvent* e);
00173     void mouseMoveEvent(QMouseEvent* e);
00174     void keyPressEvent(QKeyEvent* e);
00175     void leaveEvent(QEvent* e);
00176 
00177     void Recenter();
00178     void TransformTarget(QPainter* painter);
00179     void Zoom(float factor);
00180 
00181     void InitializePixelBuffers();
00182 
00183     bool has_pixel_buffers_;
00184     int32_t pixel_buffer_size_;
00185     GLuint pixel_buffer_ids_[2];
00186     int32_t pixel_buffer_index_;
00187     bool capture_frames_;
00188 
00189     bool initialized_;
00190     bool fix_orientation_;
00191     bool rotate_90_;
00192     bool enable_antialiasing_;
00193 
00194     QTimer frame_rate_timer_;
00195 
00196     QColor bg_color_;
00197 
00198     Qt::MouseButton mouse_button_;
00199     bool mouse_pressed_;
00200     int mouse_x_;
00201     int mouse_y_;
00202     // Used when right-click dragging to zoom
00203     int mouse_previous_y_;
00204 
00205     bool mouse_hovering_;
00206     int mouse_hover_x_;
00207     int mouse_hover_y_;
00208 
00209     // Offset based on previous mouse drags
00210     double offset_x_;
00211     double offset_y_;
00212 
00213     // Offset based on current mouse drag
00214     double drag_x_;
00215     double drag_y_;
00216 
00217     // The center of the view
00218     float view_center_x_;
00219     float view_center_y_;
00220 
00221     // View scale in meters per pixel
00222     float view_scale_;
00223 
00224     // The bounds of the view
00225     float view_left_;
00226     float view_right_;
00227     float view_top_;
00228     float view_bottom_;
00229 
00230     // The bounds of the scene
00231     float scene_left_;
00232     float scene_right_;
00233     float scene_top_;
00234     float scene_bottom_;
00235 
00236     std::string fixed_frame_;
00237     std::string target_frame_;
00238 
00239     boost::shared_ptr<tf::TransformListener> tf_;
00240     tf::StampedTransform transform_;
00241     QTransform qtransform_;
00242     std::list<MapvizPluginPtr> plugins_;
00243 
00244     std::vector<uint8_t> capture_buffer_;
00245   };
00246 }
00247 
00248 #endif  // MAPVIZ_MAP_CANVAS_H_


mapviz
Author(s): Marc Alban
autogenerated on Thu Jun 6 2019 18:50:58