map_canvas.cpp
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 
00031 #include <GL/glew.h>
00032 #include <GL/gl.h>
00033 #include <GL/glu.h>
00034 
00035 #include <mapviz/map_canvas.h>
00036 
00037 // C++ standard libraries
00038 #include <cmath>
00039 #include <swri_math_util/constants.h>
00040 
00041 namespace mapviz
00042 {
00043 bool compare_plugins(MapvizPluginPtr a, MapvizPluginPtr b)
00044 {
00045   return a->DrawOrder() < b->DrawOrder();
00046 }
00047 
00048 MapCanvas::MapCanvas(QWidget* parent) :
00049   QGLWidget(QGLFormat(QGL::SampleBuffers), parent),
00050   has_pixel_buffers_(false),
00051   pixel_buffer_size_(0),
00052   pixel_buffer_index_(0),
00053   capture_frames_(false),
00054   initialized_(false),
00055   fix_orientation_(false),
00056   rotate_90_(false),
00057   enable_antialiasing_(true),
00058   mouse_button_(Qt::NoButton),
00059   mouse_pressed_(false),
00060   mouse_x_(0),
00061   mouse_y_(0),
00062   mouse_previous_y_(0),
00063   mouse_hovering_(false),
00064   mouse_hover_x_(0),
00065   mouse_hover_y_(0),
00066   offset_x_(0),
00067   offset_y_(0),
00068   drag_x_(0),
00069   drag_y_(0),
00070   view_center_x_(0),
00071   view_center_y_(0),
00072   view_scale_(1),
00073   view_left_(-25),
00074   view_right_(25),
00075   view_top_(10),
00076   view_bottom_(-10),
00077   scene_left_(-10),
00078   scene_right_(10),
00079   scene_top_(10),
00080   scene_bottom_(-10)
00081 {
00082   ROS_INFO("View scale: %f meters/pixel", view_scale_);
00083   setMouseTracking(true);
00084 
00085   transform_.setIdentity();
00086 
00087   QObject::connect(&frame_rate_timer_, SIGNAL(timeout()), this, SLOT(update()));
00088   setFrameRate(50.0);
00089   frame_rate_timer_.start();
00090   setFocusPolicy(Qt::StrongFocus);
00091 }
00092 
00093 MapCanvas::~MapCanvas()
00094 {
00095   if(pixel_buffer_size_ != 0)
00096   {
00097     glDeleteBuffersARB(2, pixel_buffer_ids_);
00098   }
00099 }
00100 
00101 void MapCanvas::InitializeTf(boost::shared_ptr<tf::TransformListener> tf)
00102 {
00103   tf_ = tf;
00104 }
00105 
00106 void MapCanvas::InitializePixelBuffers()
00107 {
00108   if(has_pixel_buffers_)
00109   {
00110     int32_t buffer_size = width() * height() * 4;
00111 
00112     if (pixel_buffer_size_ != buffer_size)
00113     {
00114       if (pixel_buffer_size_ != 0)
00115       {
00116         glDeleteBuffersARB(2, pixel_buffer_ids_);
00117       }
00118 
00119       glGenBuffersARB(2, pixel_buffer_ids_);
00120       glBindBufferARB(GL_PIXEL_PACK_BUFFER_ARB, pixel_buffer_ids_[0]);
00121       glBufferDataARB(GL_PIXEL_PACK_BUFFER_ARB, buffer_size, 0, GL_STREAM_READ_ARB);
00122       glBindBufferARB(GL_PIXEL_PACK_BUFFER_ARB, pixel_buffer_ids_[1]);
00123       glBufferDataARB(GL_PIXEL_PACK_BUFFER_ARB, buffer_size, 0, GL_STREAM_READ_ARB);
00124       glBindBufferARB(GL_PIXEL_PACK_BUFFER_ARB, 0);
00125 
00126       pixel_buffer_size_ = buffer_size;
00127     }
00128   }
00129 }
00130 
00131 void MapCanvas::initializeGL()
00132 {
00133   GLenum err = glewInit();
00134   if (GLEW_OK != err)
00135   {
00136     ROS_ERROR("Error: %s\n", glewGetErrorString(err));
00137   }
00138   else
00139   {
00140     // Check if pixel buffers are available for asynchronous capturing
00141     std::string extensions = (const char*)glGetString(GL_EXTENSIONS);
00142     has_pixel_buffers_ = extensions.find("GL_ARB_pixel_buffer_object") != std::string::npos;
00143   }
00144 
00145   glClearColor(0.58f, 0.56f, 0.5f, 1);
00146   if (enable_antialiasing_)
00147   {
00148     glEnable(GL_MULTISAMPLE);
00149     glEnable(GL_POINT_SMOOTH);
00150     glEnable(GL_LINE_SMOOTH);
00151     glEnable(GL_POLYGON_SMOOTH);
00152     glHint(GL_LINE_SMOOTH_HINT, GL_NICEST);
00153     glHint(GL_POINT_SMOOTH_HINT, GL_NICEST);
00154     glHint(GL_POLYGON_SMOOTH_HINT, GL_NICEST);
00155   }
00156   else
00157   {
00158     glDisable(GL_MULTISAMPLE);
00159     glDisable(GL_POINT_SMOOTH);
00160     glDisable(GL_LINE_SMOOTH);
00161     glDisable(GL_POLYGON_SMOOTH);
00162   }
00163   initGlBlending();
00164 
00165   initialized_ = true;
00166 }
00167 
00168 void MapCanvas::initGlBlending()
00169 {
00170   glEnable(GL_BLEND);
00171   glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA);
00172   glDepthFunc(GL_NEVER);
00173   glDisable(GL_DEPTH_TEST);
00174 }
00175 
00176 void MapCanvas::resizeGL(int w, int h)
00177 {
00178   UpdateView();
00179 }
00180 
00181 void MapCanvas::CaptureFrame(bool force)
00182 {
00183   // Ensure the pixel size is actually 4
00184   glPixelStorei(GL_PACK_ALIGNMENT, 4);
00185 
00186   if (has_pixel_buffers_ && !force)
00187   {
00188     InitializePixelBuffers();
00189 
00190     pixel_buffer_index_ = (pixel_buffer_index_ + 1) % 2;
00191     int32_t next_index = (pixel_buffer_index_ + 1) % 2;
00192 
00193     glBindBufferARB(GL_PIXEL_PACK_BUFFER_ARB, pixel_buffer_ids_[pixel_buffer_index_]);
00194     glReadPixels(0, 0, width(), height(), GL_BGRA, GL_UNSIGNED_BYTE, 0);
00195     glBindBufferARB(GL_PIXEL_PACK_BUFFER_ARB, pixel_buffer_ids_[next_index]);
00196     GLubyte* data = reinterpret_cast<GLubyte*>(glMapBufferARB(GL_PIXEL_PACK_BUFFER_ARB, GL_READ_ONLY_ARB));
00197     if(data)
00198     {
00199       capture_buffer_.resize(pixel_buffer_size_);
00200 
00201       memcpy(&capture_buffer_[0], data, pixel_buffer_size_);
00202 
00203       glUnmapBufferARB(GL_PIXEL_PACK_BUFFER_ARB);
00204     }
00205     glBindBufferARB(GL_PIXEL_PACK_BUFFER_ARB, 0);
00206   }
00207   else
00208   {
00209     int32_t buffer_size = width() * height() * 4;
00210     capture_buffer_.clear();
00211     capture_buffer_.resize(buffer_size);
00212 
00213     glReadPixels(0, 0, width(), height(), GL_BGRA, GL_UNSIGNED_BYTE, &capture_buffer_[0]);
00214   }
00215 }
00216 
00217 void MapCanvas::paintEvent(QPaintEvent* event)
00218 {
00219   if (capture_frames_)
00220   {
00221     CaptureFrame();
00222   }
00223 
00224   QPainter p(this);
00225   p.setRenderHints(QPainter::Antialiasing |
00226                    QPainter::TextAntialiasing |
00227                    QPainter::SmoothPixmapTransform |
00228                    QPainter::HighQualityAntialiasing,
00229                    enable_antialiasing_);
00230   p.beginNativePainting();
00231   // .beginNativePainting() disables blending and clears a handful of other
00232   // values that we need to manually reset.
00233   initGlBlending();
00234   glMatrixMode(GL_MODELVIEW);
00235   glPushMatrix();
00236 
00237   glClearColor(bg_color_.redF(), bg_color_.greenF(), bg_color_.blueF(), 1.0f);
00238   UpdateView();
00239   glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
00240 
00241   TransformTarget(&p);
00242 
00243   // Draw test pattern
00244   glLineWidth(3);
00245   glBegin(GL_LINES);
00246   // Red line to the right
00247   glColor3f(1, 0, 0);
00248   glVertex2f(0, 0);
00249   glVertex2f(20, 0);
00250 
00251   // Green line to the top
00252   glColor3f(0, 1, 0);
00253   glVertex2f(0, 0);
00254   glVertex2f(0, 20);
00255   glEnd();
00256 
00257   std::list<MapvizPluginPtr>::iterator it;
00258   for (it = plugins_.begin(); it != plugins_.end(); ++it)
00259   {
00260     // Before we let a plugin do any drawing, push all matrices and attributes.
00261     // This helps to ensure that plugins can't accidentally mess something up
00262     // for the next plugin.
00263     pushGlMatrices();
00264 
00265     (*it)->DrawPlugin(view_center_x_, view_center_y_, view_scale_);
00266 
00267     if ((*it)->SupportsPainting())
00268     {
00269       p.endNativePainting();
00270       (*it)->PaintPlugin(&p, view_center_x_, view_center_y_, view_scale_);
00271       p.beginNativePainting();
00272       initGlBlending();
00273     }
00274 
00275     popGlMatrices();
00276   }
00277 
00278   glMatrixMode(GL_MODELVIEW);
00279   glPopMatrix();
00280   p.endNativePainting();
00281 }
00282 
00283 void MapCanvas::pushGlMatrices()
00284 {
00285   glMatrixMode(GL_TEXTURE);
00286   glPushMatrix();
00287   glMatrixMode(GL_PROJECTION);
00288   glPushMatrix();
00289   glMatrixMode(GL_MODELVIEW);
00290   glPushMatrix();
00291   glPushAttrib(GL_ALL_ATTRIB_BITS);
00292 }
00293 
00294 void MapCanvas::popGlMatrices()
00295 {
00296   glPopAttrib();
00297   glMatrixMode(GL_MODELVIEW);
00298   glPopMatrix();
00299   glMatrixMode(GL_PROJECTION);
00300   glPopMatrix();
00301   glMatrixMode(GL_TEXTURE);
00302   glPopMatrix();
00303 }
00304 
00305 void MapCanvas::wheelEvent(QWheelEvent* e)
00306 {
00307   float numDegrees = e->delta() / -8;
00308 
00309   Zoom(numDegrees / 10.0);
00310 }
00311 
00312 void MapCanvas::Zoom(float factor)
00313 {
00314   view_scale_ *= std::pow(1.1, factor);
00315   UpdateView();
00316 }
00317 
00318 void MapCanvas::mousePressEvent(QMouseEvent* e)
00319 {
00320   mouse_x_ = e->x();
00321   mouse_y_ = e->y();
00322   mouse_previous_y_ = mouse_y_;
00323   drag_x_ = 0;
00324   drag_y_ = 0;
00325   mouse_pressed_ = true;
00326   mouse_button_ = e->button();
00327 }
00328 
00329 void MapCanvas::keyPressEvent(QKeyEvent* event)
00330 {
00331   std::list<MapvizPluginPtr>::iterator it;
00332   for (it = plugins_.begin(); it != plugins_.end(); ++it)
00333   {
00334     (*it)->event(event);
00335   }
00336 }
00337 
00338 QPointF MapCanvas::MapGlCoordToFixedFrame(const QPointF& point)
00339 {
00340   bool invertible = true;
00341   return qtransform_.inverted(&invertible).map(point);
00342 }
00343 
00344 QPointF MapCanvas::FixedFrameToMapGlCoord(const QPointF& point)
00345 {
00346   return qtransform_.map(point);
00347 }
00348 
00349 void MapCanvas::mouseReleaseEvent(QMouseEvent* e)
00350 {
00351   mouse_button_ = Qt::NoButton;
00352   mouse_pressed_ = false;
00353   offset_x_ += drag_x_;
00354   offset_y_ += drag_y_;
00355   drag_x_ = 0;
00356   drag_y_ = 0;
00357 }
00358 
00359 void MapCanvas::mouseMoveEvent(QMouseEvent* e)
00360 {
00361   if (mouse_pressed_)
00362   {
00363     int diff;
00364     switch (mouse_button_)
00365     {
00366       case Qt::LeftButton:
00367       case Qt::MiddleButton:
00368         if (((mouse_x_ - e->x()) != 0 || (mouse_y_ - e->y()) != 0))
00369         {
00370           drag_x_ = -((mouse_x_ - e->x()) * view_scale_);
00371           drag_y_ = ((mouse_y_ - e->y()) * view_scale_);
00372         }
00373         break;
00374       case Qt::RightButton:
00375         diff = e->y() - mouse_previous_y_;
00376         if (diff != 0)
00377         {
00378           Zoom(((float)diff) / 10.0f);
00379         }
00380         mouse_previous_y_ = e->y();
00381         break;
00382       default:
00383         // Unexpected mouse button
00384         break;
00385     }
00386   }
00387 
00388   double center_x = -offset_x_ - drag_x_;
00389   double center_y = -offset_y_ - drag_y_;
00390   double x = center_x + (e->x() - width() / 2.0) * view_scale_;
00391   double y = center_y + (height() / 2.0 - e->y()) * view_scale_;
00392 
00393   tf::Point point(x, y, 0);
00394   point = transform_ * point;
00395 
00396   mouse_hovering_ = true;
00397   mouse_hover_x_ = e->x();
00398   mouse_hover_y_ = e->y();
00399 
00400   Q_EMIT Hover(point.x(), point.y(), view_scale_);
00401 }
00402 
00403 void MapCanvas::leaveEvent(QEvent* e)
00404 {
00405   mouse_hovering_ = false;
00406   Q_EMIT Hover(0, 0, 0);
00407 }
00408 
00409 void MapCanvas::SetFixedFrame(const std::string& frame)
00410 {
00411   fixed_frame_ = frame;
00412   std::list<MapvizPluginPtr>::iterator it;
00413   for (it = plugins_.begin(); it != plugins_.end(); ++it)
00414   {
00415     (*it)->SetTargetFrame(frame);
00416   }
00417 }
00418 
00419 void MapCanvas::SetTargetFrame(const std::string& frame)
00420 {
00421   offset_x_ = 0;
00422   offset_y_ = 0;
00423   drag_x_ = 0;
00424   drag_y_ = 0;
00425 
00426   target_frame_ = frame;
00427 }
00428 
00429 void MapCanvas::ToggleFixOrientation(bool on)
00430 {
00431   fix_orientation_ = on;
00432 }
00433 
00434 void MapCanvas::ToggleRotate90(bool on)
00435 {
00436   rotate_90_ = on;
00437 }
00438 
00439 void MapCanvas::ToggleEnableAntialiasing(bool on)
00440 {
00441   enable_antialiasing_ = on;
00442   QGLFormat format;
00443   format.setSwapInterval(1);
00444   format.setSampleBuffers(enable_antialiasing_);
00445   // After setting the format, initializeGL will automatically be called again, then paintGL.
00446   this->setFormat(format);
00447 }
00448 
00449 void MapCanvas::ToggleUseLatestTransforms(bool on)
00450 {
00451   std::list<MapvizPluginPtr>::iterator it;
00452   for (it = plugins_.begin(); it != plugins_.end(); ++it)
00453   {
00454     (*it)->SetUseLatestTransforms(on);
00455   }
00456 }
00457 
00458 void MapCanvas::AddPlugin(MapvizPluginPtr plugin, int order)
00459 {
00460   plugins_.push_back(plugin);
00461 }
00462 
00463 void MapCanvas::RemovePlugin(MapvizPluginPtr plugin)
00464 {
00465   plugin->Shutdown();
00466   plugins_.remove(plugin);
00467 }
00468 
00469 void MapCanvas::TransformTarget(QPainter* painter)
00470 {
00471   glTranslatef(offset_x_ + drag_x_, offset_y_ + drag_y_, 0);
00472   // In order for plugins drawing with a QPainter to be able to use the same coordinates
00473   // as plugins using drawing using native GL commands, we have to replicate the
00474   // GL transforms using a QTransform.  Note that a QPainter's coordinate system is
00475   // flipped on the Y axis relative to OpenGL's.
00476   qtransform_ = qtransform_.translate(offset_x_ + drag_x_, -(offset_y_ + drag_y_));
00477 
00478   view_center_x_ = -offset_x_ - drag_x_;
00479   view_center_y_ = -offset_y_ - drag_y_;
00480 
00481   if (!tf_ || fixed_frame_.empty() || target_frame_.empty() || target_frame_ == "<none>")
00482   {
00483     qtransform_ = qtransform_.scale(1, -1);
00484     painter->setWorldTransform(qtransform_, false);
00485 
00486     return;
00487   }
00488 
00489   bool success = false;
00490 
00491   try
00492   {
00493     tf_->lookupTransform(fixed_frame_, target_frame_, ros::Time(0), transform_);
00494 
00495     // If the viewer orientation is fixed don't rotate the center point.
00496     if (fix_orientation_)
00497     {
00498       transform_.setRotation(tf::Transform::getIdentity().getRotation());
00499     }
00500 
00501     if (rotate_90_)
00502     {
00503       transform_.setRotation(
00504           tf::createQuaternionFromYaw(-swri_math_util::_half_pi) * transform_.getRotation());
00505     }
00506 
00507     double roll, pitch, yaw;
00508     transform_.getBasis().getRPY(roll, pitch, yaw);
00509 
00510     glRotatef(-yaw * 57.2957795, 0, 0, 1);
00511     qtransform_ = qtransform_.rotateRadians(yaw);
00512 
00513     glTranslatef(-transform_.getOrigin().getX(), -transform_.getOrigin().getY(), 0);
00514     qtransform_ = qtransform_.translate(-transform_.getOrigin().getX(), transform_.getOrigin().getY());
00515 
00516     tf::Point point(view_center_x_, view_center_y_, 0);
00517 
00518     tf::Point center = transform_ * point;
00519 
00520     view_center_x_ = center.getX();
00521     view_center_y_ = center.getY();
00522 
00523     qtransform_ = qtransform_.scale(1, -1);
00524     painter->setWorldTransform(qtransform_, false);
00525 
00526     if (mouse_hovering_)
00527     {
00528       double center_x = -offset_x_ - drag_x_;
00529       double center_y = -offset_y_ - drag_y_;
00530       double x = center_x + (mouse_hover_x_ - width() / 2.0) * view_scale_;
00531       double y = center_y + (height() / 2.0  - mouse_hover_y_) * view_scale_;
00532 
00533       tf::Point hover(x, y, 0);
00534       hover = transform_ * hover;
00535 
00536       Q_EMIT Hover(hover.x(), hover.y(), view_scale_);
00537     }
00538 
00539     success = true;
00540   }
00541   catch (const tf::LookupException& e)
00542   {
00543     ROS_ERROR_THROTTLE(2.0, "%s", e.what());
00544   }
00545   catch (const tf::ConnectivityException& e)
00546   {
00547     ROS_ERROR_THROTTLE(2.0, "%s", e.what());
00548   }
00549   catch (const tf::ExtrapolationException& e)
00550   {
00551     ROS_ERROR_THROTTLE(2.0, "%s", e.what());
00552   }
00553   catch (...)
00554   {
00555     ROS_ERROR_THROTTLE(2.0, "Error looking up transform");
00556   }
00557 
00558   if (!success)
00559   {
00560     qtransform_ = qtransform_.scale(1, -1);
00561     painter->setWorldTransform(qtransform_, false);
00562   }
00563 }
00564 
00565 void MapCanvas::UpdateView()
00566 {
00567   if (initialized_)
00568   {
00569     Recenter();
00570 
00571     glViewport(0, 0, width(), height());
00572     glMatrixMode(GL_PROJECTION);
00573     glLoadIdentity();
00574     glOrtho(view_left_, view_right_, view_top_, view_bottom_, -0.5f, 0.5f);
00575 
00576     qtransform_ = QTransform::fromTranslate(width() / 2.0, height() / 2.0).
00577         scale(1.0 / view_scale_, 1.0 / view_scale_);
00578   }
00579 }
00580 
00581 void MapCanvas::ResetLocation()
00582 {
00583   SetTargetFrame(target_frame_);
00584   SetViewScale(1.0);
00585 }
00586 
00587 void MapCanvas::ReorderDisplays()
00588 {
00589   plugins_.sort(compare_plugins);
00590 }
00591 
00592 void MapCanvas::Recenter()
00593 {
00594   // Recalculate the bounds of the view
00595   view_left_ = -(width() * view_scale_ * 0.5);
00596   view_top_ = -(height() * view_scale_ * 0.5);
00597   view_right_ = (width() * view_scale_ * 0.5);
00598   view_bottom_ = (height() * view_scale_ * 0.5);
00599 }
00600 
00601 void MapCanvas::setFrameRate(const double fps)
00602 {
00603   if (fps <= 0.0) {
00604     ROS_ERROR("Invalid frame rate: %f", fps);
00605     return;
00606   }
00607 
00608   frame_rate_timer_.setInterval(1000.0/fps);
00609 }
00610 
00611 double MapCanvas::frameRate() const
00612 {
00613   return 1000.0 / frame_rate_timer_.interval();
00614 }
00615 }  // namespace mapviz


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