map_canvas.cpp
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 
31 #include <GL/glew.h>
32 #include <GL/gl.h>
33 #include <GL/glu.h>
34 
35 #include <mapviz/map_canvas.h>
36 
37 // C++ standard libraries
38 #include <cmath>
40 
41 namespace mapviz
42 {
44 {
45  return a->DrawOrder() < b->DrawOrder();
46 }
47 
48 MapCanvas::MapCanvas(QWidget* parent) :
49  QGLWidget(QGLFormat(QGL::SampleBuffers), parent),
50  has_pixel_buffers_(false),
51  pixel_buffer_size_(0),
52  pixel_buffer_index_(0),
53  capture_frames_(false),
54  initialized_(false),
55  fix_orientation_(false),
56  rotate_90_(false),
57  enable_antialiasing_(true),
58  mouse_button_(Qt::NoButton),
59  mouse_pressed_(false),
60  mouse_x_(0),
61  mouse_y_(0),
62  mouse_previous_y_(0),
63  mouse_hovering_(false),
64  mouse_hover_x_(0),
65  mouse_hover_y_(0),
66  offset_x_(0),
67  offset_y_(0),
68  drag_x_(0),
69  drag_y_(0),
70  view_center_x_(0),
71  view_center_y_(0),
72  view_scale_(1),
73  view_left_(-25),
74  view_right_(25),
75  view_top_(10),
76  view_bottom_(-10),
77  scene_left_(-10),
78  scene_right_(10),
79  scene_top_(10),
80  scene_bottom_(-10)
81 {
82  ROS_INFO("View scale: %f meters/pixel", view_scale_);
83  setMouseTracking(true);
84 
86 
87  QObject::connect(&frame_rate_timer_, SIGNAL(timeout()), this, SLOT(update()));
88  setFrameRate(50.0);
89  frame_rate_timer_.start();
90  setFocusPolicy(Qt::StrongFocus);
91 }
92 
94 {
95  if(pixel_buffer_size_ != 0)
96  {
97  glDeleteBuffersARB(2, pixel_buffer_ids_);
98  }
99 }
100 
102 {
103  tf_ = tf;
104 }
105 
107 {
109  {
110  int32_t buffer_size = width() * height() * 4;
111 
112  if (pixel_buffer_size_ != buffer_size)
113  {
114  if (pixel_buffer_size_ != 0)
115  {
116  glDeleteBuffersARB(2, pixel_buffer_ids_);
117  }
118 
119  glGenBuffersARB(2, pixel_buffer_ids_);
120  glBindBufferARB(GL_PIXEL_PACK_BUFFER_ARB, pixel_buffer_ids_[0]);
121  glBufferDataARB(GL_PIXEL_PACK_BUFFER_ARB, buffer_size, 0, GL_STREAM_READ_ARB);
122  glBindBufferARB(GL_PIXEL_PACK_BUFFER_ARB, pixel_buffer_ids_[1]);
123  glBufferDataARB(GL_PIXEL_PACK_BUFFER_ARB, buffer_size, 0, GL_STREAM_READ_ARB);
124  glBindBufferARB(GL_PIXEL_PACK_BUFFER_ARB, 0);
125 
126  pixel_buffer_size_ = buffer_size;
127  }
128  }
129 }
130 
132 {
133  GLenum err = glewInit();
134  if (GLEW_OK != err)
135  {
136  ROS_ERROR("Error: %s\n", glewGetErrorString(err));
137  }
138  else
139  {
140  // Check if pixel buffers are available for asynchronous capturing
141  std::string extensions = (const char*)glGetString(GL_EXTENSIONS);
142  has_pixel_buffers_ = extensions.find("GL_ARB_pixel_buffer_object") != std::string::npos;
143  }
144 
145  glClearColor(0.58f, 0.56f, 0.5f, 1);
147  {
148  glEnable(GL_MULTISAMPLE);
149  glEnable(GL_POINT_SMOOTH);
150  glEnable(GL_LINE_SMOOTH);
151  glEnable(GL_POLYGON_SMOOTH);
152  glHint(GL_LINE_SMOOTH_HINT, GL_NICEST);
153  glHint(GL_POINT_SMOOTH_HINT, GL_NICEST);
154  glHint(GL_POLYGON_SMOOTH_HINT, GL_NICEST);
155  }
156  else
157  {
158  glDisable(GL_MULTISAMPLE);
159  glDisable(GL_POINT_SMOOTH);
160  glDisable(GL_LINE_SMOOTH);
161  glDisable(GL_POLYGON_SMOOTH);
162  }
163  initGlBlending();
164 
165  initialized_ = true;
166 }
167 
169 {
170  glEnable(GL_BLEND);
171  glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA);
172  glDepthFunc(GL_NEVER);
173  glDisable(GL_DEPTH_TEST);
174 }
175 
176 void MapCanvas::resizeGL(int w, int h)
177 {
178  UpdateView();
179 }
180 
181 void MapCanvas::CaptureFrame(bool force)
182 {
183  // Ensure the pixel size is actually 4
184  glPixelStorei(GL_PACK_ALIGNMENT, 4);
185 
186  if (has_pixel_buffers_ && !force)
187  {
189 
191  int32_t next_index = (pixel_buffer_index_ + 1) % 2;
192 
193  glBindBufferARB(GL_PIXEL_PACK_BUFFER_ARB, pixel_buffer_ids_[pixel_buffer_index_]);
194  glReadPixels(0, 0, width(), height(), GL_BGRA, GL_UNSIGNED_BYTE, 0);
195  glBindBufferARB(GL_PIXEL_PACK_BUFFER_ARB, pixel_buffer_ids_[next_index]);
196  GLubyte* data = reinterpret_cast<GLubyte*>(glMapBufferARB(GL_PIXEL_PACK_BUFFER_ARB, GL_READ_ONLY_ARB));
197  if(data)
198  {
200 
201  memcpy(&capture_buffer_[0], data, pixel_buffer_size_);
202 
203  glUnmapBufferARB(GL_PIXEL_PACK_BUFFER_ARB);
204  }
205  glBindBufferARB(GL_PIXEL_PACK_BUFFER_ARB, 0);
206  }
207  else
208  {
209  int32_t buffer_size = width() * height() * 4;
210  capture_buffer_.clear();
211  capture_buffer_.resize(buffer_size);
212 
213  glReadPixels(0, 0, width(), height(), GL_BGRA, GL_UNSIGNED_BYTE, &capture_buffer_[0]);
214  }
215 }
216 
217 void MapCanvas::paintEvent(QPaintEvent* event)
218 {
219  if (capture_frames_)
220  {
221  CaptureFrame();
222  }
223 
224  QPainter p(this);
225  p.setRenderHints(QPainter::Antialiasing |
226  QPainter::TextAntialiasing |
227  QPainter::SmoothPixmapTransform |
228  QPainter::HighQualityAntialiasing,
230  p.beginNativePainting();
231  // .beginNativePainting() disables blending and clears a handful of other
232  // values that we need to manually reset.
233  initGlBlending();
234  glMatrixMode(GL_MODELVIEW);
235  glPushMatrix();
236 
237  glClearColor(bg_color_.redF(), bg_color_.greenF(), bg_color_.blueF(), 1.0f);
238  UpdateView();
239  glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
240 
241  TransformTarget(&p);
242 
243  // Draw test pattern
244  glLineWidth(3);
245  glBegin(GL_LINES);
246  // Red line to the right
247  glColor3f(1, 0, 0);
248  glVertex2f(0, 0);
249  glVertex2f(20, 0);
250 
251  // Green line to the top
252  glColor3f(0, 1, 0);
253  glVertex2f(0, 0);
254  glVertex2f(0, 20);
255  glEnd();
256 
257  std::list<MapvizPluginPtr>::iterator it;
258  for (it = plugins_.begin(); it != plugins_.end(); ++it)
259  {
260  // Before we let a plugin do any drawing, push all matrices and attributes.
261  // This helps to ensure that plugins can't accidentally mess something up
262  // for the next plugin.
263  pushGlMatrices();
264 
265  (*it)->DrawPlugin(view_center_x_, view_center_y_, view_scale_);
266 
267  if ((*it)->SupportsPainting())
268  {
269  p.endNativePainting();
270  (*it)->PaintPlugin(&p, view_center_x_, view_center_y_, view_scale_);
271  p.beginNativePainting();
272  initGlBlending();
273  }
274 
275  popGlMatrices();
276  }
277 
278  glMatrixMode(GL_MODELVIEW);
279  glPopMatrix();
280  p.endNativePainting();
281 }
282 
284 {
285  glMatrixMode(GL_TEXTURE);
286  glPushMatrix();
287  glMatrixMode(GL_PROJECTION);
288  glPushMatrix();
289  glMatrixMode(GL_MODELVIEW);
290  glPushMatrix();
291  glPushAttrib(GL_ALL_ATTRIB_BITS);
292 }
293 
295 {
296  glPopAttrib();
297  glMatrixMode(GL_MODELVIEW);
298  glPopMatrix();
299  glMatrixMode(GL_PROJECTION);
300  glPopMatrix();
301  glMatrixMode(GL_TEXTURE);
302  glPopMatrix();
303 }
304 
305 void MapCanvas::wheelEvent(QWheelEvent* e)
306 {
307  float numDegrees = e->delta() / -8;
308 
309  Zoom(numDegrees / 10.0);
310 }
311 
312 void MapCanvas::Zoom(float factor)
313 {
314  view_scale_ *= std::pow(1.1, factor);
315  UpdateView();
316 }
317 
318 void MapCanvas::mousePressEvent(QMouseEvent* e)
319 {
320  mouse_x_ = e->x();
321  mouse_y_ = e->y();
323  drag_x_ = 0;
324  drag_y_ = 0;
325  mouse_pressed_ = true;
326  mouse_button_ = e->button();
327 }
328 
329 void MapCanvas::keyPressEvent(QKeyEvent* event)
330 {
331  std::list<MapvizPluginPtr>::iterator it;
332  for (it = plugins_.begin(); it != plugins_.end(); ++it)
333  {
334  (*it)->event(event);
335  }
336 }
337 
338 QPointF MapCanvas::MapGlCoordToFixedFrame(const QPointF& point)
339 {
340  bool invertible = true;
341  return qtransform_.inverted(&invertible).map(point);
342 }
343 
344 QPointF MapCanvas::FixedFrameToMapGlCoord(const QPointF& point)
345 {
346  return qtransform_.map(point);
347 }
348 
349 void MapCanvas::mouseReleaseEvent(QMouseEvent* e)
350 {
351  mouse_button_ = Qt::NoButton;
352  mouse_pressed_ = false;
353  offset_x_ += drag_x_;
354  offset_y_ += drag_y_;
355  drag_x_ = 0;
356  drag_y_ = 0;
357 }
358 
359 void MapCanvas::mouseMoveEvent(QMouseEvent* e)
360 {
361  if (mouse_pressed_)
362  {
363  int diff;
364  switch (mouse_button_)
365  {
366  case Qt::LeftButton:
367  case Qt::MiddleButton:
368  if (((mouse_x_ - e->x()) != 0 || (mouse_y_ - e->y()) != 0))
369  {
370  drag_x_ = -((mouse_x_ - e->x()) * view_scale_);
371  drag_y_ = ((mouse_y_ - e->y()) * view_scale_);
372  }
373  break;
374  case Qt::RightButton:
375  diff = e->y() - mouse_previous_y_;
376  if (diff != 0)
377  {
378  Zoom(((float)diff) / 10.0f);
379  }
380  mouse_previous_y_ = e->y();
381  break;
382  default:
383  // Unexpected mouse button
384  break;
385  }
386  }
387 
388  double center_x = -offset_x_ - drag_x_;
389  double center_y = -offset_y_ - drag_y_;
390  double x = center_x + (e->x() - width() / 2.0) * view_scale_;
391  double y = center_y + (height() / 2.0 - e->y()) * view_scale_;
392 
393  tf::Point point(x, y, 0);
394  point = transform_ * point;
395 
396  mouse_hovering_ = true;
397  mouse_hover_x_ = e->x();
398  mouse_hover_y_ = e->y();
399 
400  Q_EMIT Hover(point.x(), point.y(), view_scale_);
401 }
402 
403 void MapCanvas::leaveEvent(QEvent* e)
404 {
405  mouse_hovering_ = false;
406  Q_EMIT Hover(0, 0, 0);
407 }
408 
409 void MapCanvas::SetFixedFrame(const std::string& frame)
410 {
411  fixed_frame_ = frame;
412  std::list<MapvizPluginPtr>::iterator it;
413  for (it = plugins_.begin(); it != plugins_.end(); ++it)
414  {
415  (*it)->SetTargetFrame(frame);
416  }
417 }
418 
419 void MapCanvas::SetTargetFrame(const std::string& frame)
420 {
421  offset_x_ = 0;
422  offset_y_ = 0;
423  drag_x_ = 0;
424  drag_y_ = 0;
425 
426  target_frame_ = frame;
427 }
428 
430 {
431  fix_orientation_ = on;
432 }
433 
435 {
436  rotate_90_ = on;
437 }
438 
440 {
442  QGLFormat format;
443  format.setSwapInterval(1);
444  format.setSampleBuffers(enable_antialiasing_);
445  // After setting the format, initializeGL will automatically be called again, then paintGL.
446  this->setFormat(format);
447 }
448 
450 {
451  std::list<MapvizPluginPtr>::iterator it;
452  for (it = plugins_.begin(); it != plugins_.end(); ++it)
453  {
454  (*it)->SetUseLatestTransforms(on);
455  }
456 }
457 
458 void MapCanvas::AddPlugin(MapvizPluginPtr plugin, int order)
459 {
460  plugins_.push_back(plugin);
461 }
462 
464 {
465  plugin->Shutdown();
466  plugins_.remove(plugin);
467 }
468 
469 void MapCanvas::TransformTarget(QPainter* painter)
470 {
471  glTranslatef(offset_x_ + drag_x_, offset_y_ + drag_y_, 0);
472  // In order for plugins drawing with a QPainter to be able to use the same coordinates
473  // as plugins using drawing using native GL commands, we have to replicate the
474  // GL transforms using a QTransform. Note that a QPainter's coordinate system is
475  // flipped on the Y axis relative to OpenGL's.
477 
480 
481  if (!tf_ || fixed_frame_.empty() || target_frame_.empty() || target_frame_ == "<none>")
482  {
483  qtransform_ = qtransform_.scale(1, -1);
484  painter->setWorldTransform(qtransform_, false);
485 
486  return;
487  }
488 
489  bool success = false;
490 
491  try
492  {
493  tf_->lookupTransform(fixed_frame_, target_frame_, ros::Time(0), transform_);
494 
495  // If the viewer orientation is fixed don't rotate the center point.
496  if (fix_orientation_)
497  {
499  }
500 
501  if (rotate_90_)
502  {
505  }
506 
507  double roll, pitch, yaw;
508  transform_.getBasis().getRPY(roll, pitch, yaw);
509 
510  glRotatef(-yaw * 57.2957795, 0, 0, 1);
511  qtransform_ = qtransform_.rotateRadians(yaw);
512 
513  glTranslatef(-transform_.getOrigin().getX(), -transform_.getOrigin().getY(), 0);
514  qtransform_ = qtransform_.translate(-transform_.getOrigin().getX(), transform_.getOrigin().getY());
515 
517 
518  tf::Point center = transform_ * point;
519 
520  view_center_x_ = center.getX();
521  view_center_y_ = center.getY();
522 
523  qtransform_ = qtransform_.scale(1, -1);
524  painter->setWorldTransform(qtransform_, false);
525 
526  if (mouse_hovering_)
527  {
528  double center_x = -offset_x_ - drag_x_;
529  double center_y = -offset_y_ - drag_y_;
530  double x = center_x + (mouse_hover_x_ - width() / 2.0) * view_scale_;
531  double y = center_y + (height() / 2.0 - mouse_hover_y_) * view_scale_;
532 
533  tf::Point hover(x, y, 0);
534  hover = transform_ * hover;
535 
536  Q_EMIT Hover(hover.x(), hover.y(), view_scale_);
537  }
538 
539  success = true;
540  }
541  catch (const tf::LookupException& e)
542  {
543  ROS_ERROR_THROTTLE(2.0, "%s", e.what());
544  }
545  catch (const tf::ConnectivityException& e)
546  {
547  ROS_ERROR_THROTTLE(2.0, "%s", e.what());
548  }
549  catch (const tf::ExtrapolationException& e)
550  {
551  ROS_ERROR_THROTTLE(2.0, "%s", e.what());
552  }
553  catch (...)
554  {
555  ROS_ERROR_THROTTLE(2.0, "Error looking up transform");
556  }
557 
558  if (!success)
559  {
560  qtransform_ = qtransform_.scale(1, -1);
561  painter->setWorldTransform(qtransform_, false);
562  }
563 }
564 
566 {
567  if (initialized_)
568  {
569  Recenter();
570 
571  glViewport(0, 0, width(), height());
572  glMatrixMode(GL_PROJECTION);
573  glLoadIdentity();
574  glOrtho(view_left_, view_right_, view_top_, view_bottom_, -0.5f, 0.5f);
575 
576  qtransform_ = QTransform::fromTranslate(width() / 2.0, height() / 2.0).
577  scale(1.0 / view_scale_, 1.0 / view_scale_);
578  }
579 }
580 
582 {
584  SetViewScale(1.0);
585 }
586 
588 {
590 }
591 
593 {
594  // Recalculate the bounds of the view
595  view_left_ = -(width() * view_scale_ * 0.5);
596  view_top_ = -(height() * view_scale_ * 0.5);
597  view_right_ = (width() * view_scale_ * 0.5);
598  view_bottom_ = (height() * view_scale_ * 0.5);
599 }
600 
601 void MapCanvas::setFrameRate(const double fps)
602 {
603  if (fps <= 0.0) {
604  ROS_ERROR("Invalid frame rate: %f", fps);
605  return;
606  }
607 
608  frame_rate_timer_.setInterval(1000.0/fps);
609 }
610 
611 double MapCanvas::frameRate() const
612 {
613  return 1000.0 / frame_rate_timer_.interval();
614 }
615 } // namespace mapviz
static const long double _half_pi
void mouseMoveEvent(QMouseEvent *e)
Definition: map_canvas.cpp:359
TFSIMD_FORCE_INLINE void setRotation(const Quaternion &q)
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
f
void CaptureFrame(bool force=false)
Definition: map_canvas.cpp:181
void resizeGL(int w, int h)
Definition: map_canvas.cpp:176
TFSIMD_FORCE_INLINE Matrix3x3 & getBasis()
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
data
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
TFSIMD_FORCE_INLINE const tfScalar & getY() const
void SetFixedFrame(const std::string &frame)
Definition: map_canvas.cpp:409
std::string fixed_frame_
Definition: map_canvas.h:236
TFSIMD_FORCE_INLINE const tfScalar & y() const
int32_t pixel_buffer_index_
Definition: map_canvas.h:186
bool compare_plugins(MapvizPluginPtr a, MapvizPluginPtr b)
Definition: map_canvas.cpp:43
void setIdentity()
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
static Quaternion createQuaternionFromYaw(double yaw)
QPointF FixedFrameToMapGlCoord(const QPointF &point)
Definition: map_canvas.cpp:344
void getRPY(tfScalar &roll, tfScalar &pitch, tfScalar &yaw, unsigned int solution_number=1) const
#define ROS_INFO(...)
#define ROS_ERROR_THROTTLE(period,...)
void InitializePixelBuffers()
Definition: map_canvas.cpp:106
TFSIMD_FORCE_INLINE const tfScalar & x() const
void ToggleRotate90(bool on)
Definition: map_canvas.cpp:434
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
void Hover(double x, double y, double scale)
std::string target_frame_
Definition: map_canvas.h:237
void ToggleUseLatestTransforms(bool on)
Definition: map_canvas.cpp:449
void SetTargetFrame(const std::string &frame)
Definition: map_canvas.cpp:419
Quaternion getRotation() const
std::list< MapvizPluginPtr > plugins_
Definition: map_canvas.h:242
double frameRate() const
Definition: map_canvas.cpp:611
TFSIMD_FORCE_INLINE const tfScalar & getX() const
static const Transform & getIdentity()
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
#define ROS_ERROR(...)
MapCanvas(QWidget *parent=0)
Definition: map_canvas.cpp:48


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