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 
88  void setCanvasAbleToMove(bool assigning)
89  {
90  canvas_able_to_move_ = assigning;
91  }
92 
93  void leaveEvent(QEvent* e);
94 
95  void SetViewScale(float scale)
96  {
97  view_scale_ = scale;
98  UpdateView();
99  }
100 
101  void SetOffsetX(float x)
102  {
103  offset_x_ = x;
104  UpdateView();
105  }
106 
107  void SetOffsetY(float y)
108  {
109  offset_y_ = y;
110  UpdateView();
111  }
112 
113  void SetBackground(const QColor& color)
114  {
115  bg_color_ = color;
116  update();
117  }
118 
119  void CaptureFrames(bool enabled)
120  {
121  capture_frames_ = enabled;
122  update();
123  }
124 
132  bool CopyCaptureBuffer(uchar* buffer)
133  {
134  if (!capture_buffer_.empty())
135  {
136  memcpy(&buffer[0], &capture_buffer_[0], capture_buffer_.size());
137  return true;
138  }
139 
140  return false;
141  }
142 
149  bool CopyCaptureBuffer(std::vector<uint8_t>& buffer)
150  {
151  buffer.clear();
152  if (!capture_buffer_.empty())
153  {
154  buffer.resize(capture_buffer_.size());
155  memcpy(&buffer[0], &capture_buffer_[0], buffer.size());
156 
157  return true;
158  }
159 
160  return false;
161  }
162 
163  void CaptureFrame(bool force = false);
164 
165  Q_SIGNALS:
166  void Hover(double x, double y, double scale);
167 
168  public Q_SLOTS:
169  void setFrameRate(const double fps);
170 
171  protected:
172  void initializeGL();
173  void initGlBlending();
174  void pushGlMatrices();
175  void popGlMatrices();
176  void resizeGL(int w, int h);
177  void paintEvent(QPaintEvent* event);
178  void wheelEvent(QWheelEvent* e);
179  void mousePressEvent(QMouseEvent* e);
180  void mouseReleaseEvent(QMouseEvent* e);
181  void mouseMoveEvent(QMouseEvent* e);
182  void keyPressEvent(QKeyEvent* e);
183 
184  void Recenter();
185  void TransformTarget(QPainter* painter);
186  void Zoom(float factor);
187 
188  void InitializePixelBuffers();
189 
190  bool canvas_able_to_move_ = true;
193  GLuint pixel_buffer_ids_[2];
196 
201 
203 
204  QColor bg_color_;
205 
206  Qt::MouseButton mouse_button_;
208  int mouse_x_;
209  int mouse_y_;
210  // Used when right-click dragging to zoom
212 
216 
217  // Offset based on previous mouse drags
218  double offset_x_;
219  double offset_y_;
220 
221  // Offset based on current mouse drag
222  double drag_x_;
223  double drag_y_;
224 
225  // The center of the view
228 
229  // View scale in meters per pixel
230  float view_scale_;
231 
232  // The bounds of the view
233  float view_left_;
234  float view_right_;
235  float view_top_;
237 
238  // The bounds of the scene
239  float scene_left_;
241  float scene_top_;
243 
244  std::string fixed_frame_;
245  std::string target_frame_;
246 
249  QTransform qtransform_;
250  std::list<MapvizPluginPtr> plugins_;
251 
252  std::vector<uint8_t> capture_buffer_;
253  };
254 }
255 
256 #endif // MAPVIZ_MAP_CANVAS_H_
void mouseMoveEvent(QMouseEvent *e)
Definition: map_canvas.cpp:361
void CaptureFrames(bool enabled)
Definition: map_canvas.h:119
QPointF MapGlCoordToFixedFrame(const QPointF &point)
Definition: map_canvas.cpp:340
void RemovePlugin(MapvizPluginPtr plugin)
Definition: map_canvas.cpp:465
void setFrameRate(const double fps)
Definition: map_canvas.cpp:605
void TransformTarget(QPainter *painter)
Definition: map_canvas.cpp:473
void CaptureFrame(bool force=false)
Definition: map_canvas.cpp:183
void resizeGL(int w, int h)
Definition: map_canvas.cpp:178
float OffsetX() const
Definition: map_canvas.h:84
std::vector< uint8_t > capture_buffer_
Definition: map_canvas.h:252
boost::shared_ptr< tf::TransformListener > tf_
Definition: map_canvas.h:247
void keyPressEvent(QKeyEvent *e)
Definition: map_canvas.cpp:331
void leaveEvent(QEvent *e)
Definition: map_canvas.cpp:405
void InitializeTf(boost::shared_ptr< tf::TransformListener > tf)
Definition: map_canvas.cpp:103
Qt::MouseButton mouse_button_
Definition: map_canvas.h:206
QTimer frame_rate_timer_
Definition: map_canvas.h:202
tf::StampedTransform transform_
Definition: map_canvas.h:248
void ToggleEnableAntialiasing(bool on)
Definition: map_canvas.cpp:441
void SetFixedFrame(const std::string &frame)
Definition: map_canvas.cpp:411
float OffsetY() const
Definition: map_canvas.h:85
std::string fixed_frame_
Definition: map_canvas.h:244
int32_t pixel_buffer_index_
Definition: map_canvas.h:194
void SetBackground(const QColor &color)
Definition: map_canvas.h:113
void setCanvasAbleToMove(bool assigning)
Definition: map_canvas.h:88
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
bool canvas_able_to_move_
Definition: map_canvas.h:190
int32_t pixel_buffer_size_
Definition: map_canvas.h:192
bool enable_antialiasing_
Definition: map_canvas.h:200
void wheelEvent(QWheelEvent *e)
Definition: map_canvas.cpp:307
void mouseReleaseEvent(QMouseEvent *e)
Definition: map_canvas.cpp:351
GLuint pixel_buffer_ids_[2]
Definition: map_canvas.h:193
QTransform qtransform_
Definition: map_canvas.h:249
QPointF FixedFrameToMapGlCoord(const QPointF &point)
Definition: map_canvas.cpp:346
double frameRate() const
Definition: map_canvas.cpp:615
void InitializePixelBuffers()
Definition: map_canvas.cpp:108
void ToggleRotate90(bool on)
Definition: map_canvas.cpp:436
void Hover(double x, double y, double scale)
std::string target_frame_
Definition: map_canvas.h:245
void SetOffsetY(float y)
Definition: map_canvas.h:107
bool CopyCaptureBuffer(uchar *buffer)
Definition: map_canvas.h:132
void SetOffsetX(float x)
Definition: map_canvas.h:101
void ToggleUseLatestTransforms(bool on)
Definition: map_canvas.cpp:451
void SetTargetFrame(const std::string &frame)
Definition: map_canvas.cpp:421
std::list< MapvizPluginPtr > plugins_
Definition: map_canvas.h:250
void ToggleFixOrientation(bool on)
Definition: map_canvas.cpp:431
void paintEvent(QPaintEvent *event)
Definition: map_canvas.cpp:219
void Zoom(float factor)
Definition: map_canvas.cpp:314
void SetViewScale(float scale)
Definition: map_canvas.h:95
float ViewScale() const
Definition: map_canvas.h:83
void mousePressEvent(QMouseEvent *e)
Definition: map_canvas.cpp:320
void AddPlugin(MapvizPluginPtr plugin, int order)
Definition: map_canvas.cpp:460
bool CopyCaptureBuffer(std::vector< uint8_t > &buffer)
Definition: map_canvas.h:149
MapCanvas(QWidget *parent=0)
Definition: map_canvas.cpp:50


mapviz
Author(s): Marc Alban
autogenerated on Fri Dec 16 2022 03:59:30