map_canvas.h
Go to the documentation of this file.
1 // *****************************************************************************
2 //
3 // Copyright (c) 2014, Southwest Research Institute® (SwRI®)
4 // All rights reserved.
5 //
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions are met:
8 // * Redistributions of source code must retain the above copyright
9 // notice, this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of Southwest Research Institute® (SwRI®) nor the
14 // names of its contributors may be used to endorse or promote products
15 // derived from this software without specific prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT HOLDER> BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //
28 // *****************************************************************************
29 
30 #ifndef MAPVIZ_MAP_CANVAS_H_
31 #define MAPVIZ_MAP_CANVAS_H_
32 
33 // C++ standard libraries
34 #include <cstring>
35 #include <list>
36 #include <string>
37 #include <vector>
38 
39 #include <boost/shared_ptr.hpp>
40 
41 // QT libraries
42 #include <QGLWidget>
43 #include <QMouseEvent>
44 #include <QWheelEvent>
45 #include <QColor>
46 #include <QTimer>
47 
48 // ROS libraries
49 #include <ros/ros.h>
50 #include <tf/transform_datatypes.h>
51 #include <tf/transform_listener.h>
52 
53 #include <mapviz/mapviz_plugin.h>
54 
55 namespace mapviz
56 {
57  class MapCanvas : public QGLWidget
58  {
59  Q_OBJECT
60 
61  public:
62  explicit MapCanvas(QWidget *parent = 0);
63  ~MapCanvas();
64 
66 
67  void AddPlugin(MapvizPluginPtr plugin, int order);
68  void RemovePlugin(MapvizPluginPtr plugin);
69  void SetFixedFrame(const std::string& frame);
70  void SetTargetFrame(const std::string& frame);
71  void ToggleFixOrientation(bool on);
72  void ToggleRotate90(bool on);
73  void ToggleEnableAntialiasing(bool on);
74  void ToggleUseLatestTransforms(bool on);
75  void UpdateView();
76  void ReorderDisplays();
77  void ResetLocation();
78  QPointF MapGlCoordToFixedFrame(const QPointF& point);
79  QPointF FixedFrameToMapGlCoord(const QPointF& point);
80 
81  double frameRate() const;
82 
83  float ViewScale() const { return view_scale_; }
84  float OffsetX() const { return offset_x_; }
85  float OffsetY() const { return offset_y_; }
86 
87  void SetViewScale(float scale)
88  {
89  view_scale_ = scale;
90  UpdateView();
91  }
92 
93  void SetOffsetX(float x)
94  {
95  offset_x_ = x;
96  UpdateView();
97  }
98 
99  void SetOffsetY(float y)
100  {
101  offset_y_ = y;
102  UpdateView();
103  }
104 
105  void SetBackground(const QColor& color)
106  {
107  bg_color_ = color;
108  update();
109  }
110 
111  void CaptureFrames(bool enabled)
112  {
113  capture_frames_ = enabled;
114  update();
115  }
116 
124  bool CopyCaptureBuffer(uchar* buffer)
125  {
126  if (!capture_buffer_.empty())
127  {
128  memcpy(&buffer[0], &capture_buffer_[0], capture_buffer_.size());
129  return true;
130  }
131 
132  return false;
133  }
134 
141  bool CopyCaptureBuffer(std::vector<uint8_t>& buffer)
142  {
143  buffer.clear();
144  if (!capture_buffer_.empty())
145  {
146  buffer.resize(capture_buffer_.size());
147  memcpy(&buffer[0], &capture_buffer_[0], buffer.size());
148 
149  return true;
150  }
151 
152  return false;
153  }
154 
155  void CaptureFrame(bool force = false);
156 
157  Q_SIGNALS:
158  void Hover(double x, double y, double scale);
159 
160  public Q_SLOTS:
161  void setFrameRate(const double fps);
162 
163  protected:
164  void initializeGL();
165  void initGlBlending();
166  void pushGlMatrices();
167  void popGlMatrices();
168  void resizeGL(int w, int h);
169  void paintEvent(QPaintEvent* event);
170  void wheelEvent(QWheelEvent* e);
171  void mousePressEvent(QMouseEvent* e);
172  void mouseReleaseEvent(QMouseEvent* e);
173  void mouseMoveEvent(QMouseEvent* e);
174  void keyPressEvent(QKeyEvent* e);
175  void leaveEvent(QEvent* e);
176 
177  void Recenter();
178  void TransformTarget(QPainter* painter);
179  void Zoom(float factor);
180 
181  void InitializePixelBuffers();
182 
185  GLuint pixel_buffer_ids_[2];
188 
193 
195 
196  QColor bg_color_;
197 
198  Qt::MouseButton mouse_button_;
200  int mouse_x_;
201  int mouse_y_;
202  // Used when right-click dragging to zoom
204 
208 
209  // Offset based on previous mouse drags
210  double offset_x_;
211  double offset_y_;
212 
213  // Offset based on current mouse drag
214  double drag_x_;
215  double drag_y_;
216 
217  // The center of the view
220 
221  // View scale in meters per pixel
222  float view_scale_;
223 
224  // The bounds of the view
225  float view_left_;
226  float view_right_;
227  float view_top_;
229 
230  // The bounds of the scene
231  float scene_left_;
233  float scene_top_;
235 
236  std::string fixed_frame_;
237  std::string target_frame_;
238 
241  QTransform qtransform_;
242  std::list<MapvizPluginPtr> plugins_;
243 
244  std::vector<uint8_t> capture_buffer_;
245  };
246 }
247 
248 #endif // MAPVIZ_MAP_CANVAS_H_
void mouseMoveEvent(QMouseEvent *e)
Definition: map_canvas.cpp:359
void CaptureFrames(bool enabled)
Definition: map_canvas.h:111
QPointF MapGlCoordToFixedFrame(const QPointF &point)
Definition: map_canvas.cpp:338
void RemovePlugin(MapvizPluginPtr plugin)
Definition: map_canvas.cpp:463
void setFrameRate(const double fps)
Definition: map_canvas.cpp:601
void TransformTarget(QPainter *painter)
Definition: map_canvas.cpp:469
void CaptureFrame(bool force=false)
Definition: map_canvas.cpp:181
void resizeGL(int w, int h)
Definition: map_canvas.cpp:176
std::vector< uint8_t > capture_buffer_
Definition: map_canvas.h:244
boost::shared_ptr< tf::TransformListener > tf_
Definition: map_canvas.h:239
void keyPressEvent(QKeyEvent *e)
Definition: map_canvas.cpp:329
void leaveEvent(QEvent *e)
Definition: map_canvas.cpp:403
void InitializeTf(boost::shared_ptr< tf::TransformListener > tf)
Definition: map_canvas.cpp:101
Qt::MouseButton mouse_button_
Definition: map_canvas.h:198
QTimer frame_rate_timer_
Definition: map_canvas.h:194
tf::StampedTransform transform_
Definition: map_canvas.h:240
void ToggleEnableAntialiasing(bool on)
Definition: map_canvas.cpp:439
void SetFixedFrame(const std::string &frame)
Definition: map_canvas.cpp:409
float OffsetX() const
Definition: map_canvas.h:84
std::string fixed_frame_
Definition: map_canvas.h:236
int32_t pixel_buffer_index_
Definition: map_canvas.h:186
TFSIMD_FORCE_INLINE const tfScalar & y() const
void SetBackground(const QColor &color)
Definition: map_canvas.h:105
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
int32_t pixel_buffer_size_
Definition: map_canvas.h:184
bool enable_antialiasing_
Definition: map_canvas.h:192
void wheelEvent(QWheelEvent *e)
Definition: map_canvas.cpp:305
void mouseReleaseEvent(QMouseEvent *e)
Definition: map_canvas.cpp:349
GLuint pixel_buffer_ids_[2]
Definition: map_canvas.h:185
QTransform qtransform_
Definition: map_canvas.h:241
QPointF FixedFrameToMapGlCoord(const QPointF &point)
Definition: map_canvas.cpp:344
void InitializePixelBuffers()
Definition: map_canvas.cpp:106
TFSIMD_FORCE_INLINE const tfScalar & x() const
void ToggleRotate90(bool on)
Definition: map_canvas.cpp:434
void Hover(double x, double y, double scale)
std::string target_frame_
Definition: map_canvas.h:237
void SetOffsetY(float y)
Definition: map_canvas.h:99
TFSIMD_FORCE_INLINE const tfScalar & w() const
float ViewScale() const
Definition: map_canvas.h:83
bool CopyCaptureBuffer(uchar *buffer)
Definition: map_canvas.h:124
void SetOffsetX(float x)
Definition: map_canvas.h:93
void ToggleUseLatestTransforms(bool on)
Definition: map_canvas.cpp:449
void SetTargetFrame(const std::string &frame)
Definition: map_canvas.cpp:419
std::list< MapvizPluginPtr > plugins_
Definition: map_canvas.h:242
double frameRate() const
Definition: map_canvas.cpp:611
void ToggleFixOrientation(bool on)
Definition: map_canvas.cpp:429
void paintEvent(QPaintEvent *event)
Definition: map_canvas.cpp:217
void Zoom(float factor)
Definition: map_canvas.cpp:312
void SetViewScale(float scale)
Definition: map_canvas.h:87
void mousePressEvent(QMouseEvent *e)
Definition: map_canvas.cpp:318
void AddPlugin(MapvizPluginPtr plugin, int order)
Definition: map_canvas.cpp:458
bool CopyCaptureBuffer(std::vector< uint8_t > &buffer)
Definition: map_canvas.h:141
MapCanvas(QWidget *parent=0)
Definition: map_canvas.cpp:48
float OffsetY() const
Definition: map_canvas.h:85


mapviz
Author(s): Marc Alban
autogenerated on Thu Jun 6 2019 19:25:08