plan_route_plugin.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 #include <mapviz_plugins/plan_route_plugin.h>
00031 
00032 // C++ standard libraries
00033 #include <cstdio>
00034 #include <vector>
00035 
00036 // QT libraries
00037 #include <QDateTime>
00038 #include <QDialog>
00039 #include <QGLWidget>
00040 #include <QMouseEvent>
00041 #include <QPainter>
00042 #include <QPalette>
00043 #include <QStaticText>
00044 
00045 #include <opencv2/core/core.hpp>
00046 
00047 // ROS libraries
00048 #include <ros/master.h>
00049 
00050 #include <swri_route_util/util.h>
00051 #include <swri_transform_util/frames.h>
00052 
00053 #include <marti_nav_msgs/PlanRoute.h>
00054 
00055 // Declare plugin
00056 #include <pluginlib/class_list_macros.h>
00057 PLUGINLIB_EXPORT_CLASS(mapviz_plugins::PlanRoutePlugin, mapviz::MapvizPlugin)
00058 
00059 namespace mnm = marti_nav_msgs;
00060 namespace sru = swri_route_util;
00061 namespace stu = swri_transform_util;
00062 
00063 namespace mapviz_plugins
00064 {
00065   PlanRoutePlugin::PlanRoutePlugin() :
00066     config_widget_(new QWidget()),
00067     map_canvas_(NULL),
00068     failed_service_(false),
00069     selected_point_(-1),
00070     is_mouse_down_(false),
00071     max_ms_(Q_INT64_C(500)),
00072     max_distance_(2.0)
00073   {
00074     ui_.setupUi(config_widget_);
00075 
00076     ui_.color->setColor(Qt::green);
00077     // Set background white
00078     QPalette p(config_widget_->palette());
00079     p.setColor(QPalette::Background, Qt::white);
00080     config_widget_->setPalette(p);
00081     // Set status text red
00082     QPalette p3(ui_.status->palette());
00083     p3.setColor(QPalette::Text, Qt::red);
00084     ui_.status->setPalette(p3);
00085     QObject::connect(ui_.service, SIGNAL(editingFinished()), this,
00086                      SLOT(PlanRoute()));
00087     QObject::connect(ui_.publish, SIGNAL(clicked()), this,
00088                      SLOT(PublishRoute()));
00089     QObject::connect(ui_.clear, SIGNAL(clicked()), this,
00090                      SLOT(Clear()));
00091   }
00092 
00093   PlanRoutePlugin::~PlanRoutePlugin()
00094   {
00095     if (map_canvas_)
00096     {
00097       map_canvas_->removeEventFilter(this);
00098     }
00099   }
00100 
00101   void PlanRoutePlugin::PublishRoute()
00102   {
00103     if (route_preview_)
00104     {
00105       if (route_topic_ != ui_.topic->text().toStdString())
00106       {
00107         route_topic_ = ui_.topic->text().toStdString();
00108         route_pub_.shutdown();
00109         route_pub_ = node_.advertise<sru::Route>(route_topic_, 1, true);
00110       }
00111 
00112       route_pub_.publish(route_preview_);
00113     }
00114   }
00115 
00116   void PlanRoutePlugin::PlanRoute()
00117   {
00118     route_preview_ = sru::RoutePtr();
00119     bool start_from_vehicle = ui_.start_from_vehicle->isChecked();
00120     if (waypoints_.size() + start_from_vehicle < 2)
00121     {
00122       return;
00123     }
00124 
00125     std::string service = ui_.service->text().toStdString();
00126     ros::ServiceClient client = node_.serviceClient<mnm::PlanRoute>(service);
00127 
00128     mnm::PlanRoute plan_route;
00129     plan_route.request.header.frame_id = stu::_wgs84_frame;
00130     plan_route.request.header.stamp = ros::Time::now();
00131     plan_route.request.plan_from_vehicle = static_cast<unsigned char>(start_from_vehicle);
00132     plan_route.request.waypoints = waypoints_;
00133 
00134     if (client.call(plan_route))
00135     {
00136       if (plan_route.response.success)
00137       {
00138         route_preview_ = boost::make_shared<sru::Route>(plan_route.response.route);
00139         failed_service_ = false;
00140       }
00141       else
00142       {
00143         PrintError(plan_route.response.message);
00144         failed_service_ = true;
00145       }
00146     }
00147     else
00148     {
00149       PrintError("Failed to plan route.");
00150       failed_service_ = true;
00151     }
00152   }
00153 
00154   void PlanRoutePlugin::Retry(const ros::TimerEvent& e)
00155   {
00156     PlanRoute();
00157   }
00158 
00159   void PlanRoutePlugin::Clear()
00160   {
00161     waypoints_.clear();
00162     route_preview_ = sru::RoutePtr();
00163   }
00164 
00165   void PlanRoutePlugin::PrintError(const std::string& message)
00166   {
00167     PrintErrorHelper(ui_.status, message, 1.0);
00168   }
00169 
00170   void PlanRoutePlugin::PrintInfo(const std::string& message)
00171   {
00172     PrintInfoHelper(ui_.status, message, 1.0);
00173   }
00174 
00175   void PlanRoutePlugin::PrintWarning(const std::string& message)
00176   {
00177     PrintWarningHelper(ui_.status, message, 1.0);
00178   }
00179 
00180   QWidget* PlanRoutePlugin::GetConfigWidget(QWidget* parent)
00181   {
00182     config_widget_->setParent(parent);
00183 
00184     return config_widget_;
00185   }
00186 
00187   bool PlanRoutePlugin::Initialize(QGLWidget* canvas)
00188   {
00189     map_canvas_ = static_cast<mapviz::MapCanvas*>(canvas);
00190     map_canvas_->installEventFilter(this);
00191 
00192     retry_timer_ = node_.createTimer(ros::Duration(1), &PlanRoutePlugin::Retry, this);
00193 
00194     initialized_ = true;
00195     return true;
00196   }
00197 
00198   bool PlanRoutePlugin::eventFilter(QObject *object, QEvent* event)
00199   {
00200     switch (event->type())
00201     {
00202       case QEvent::MouseButtonPress:
00203         return handleMousePress(static_cast<QMouseEvent*>(event));
00204       case QEvent::MouseButtonRelease:
00205         return handleMouseRelease(static_cast<QMouseEvent*>(event));
00206       case QEvent::MouseMove:
00207         return handleMouseMove(static_cast<QMouseEvent*>(event));
00208       default:
00209         return false;
00210     }
00211   }
00212 
00213   bool PlanRoutePlugin::handleMousePress(QMouseEvent* event)
00214   {
00215     selected_point_ = -1;
00216     int closest_point = 0;
00217     double closest_distance = std::numeric_limits<double>::max();
00218 
00219 #if QT_VERSION >= 0x050000
00220     QPointF point = event->localPos();
00221 #else
00222     QPointF point = event->posF();
00223 #endif
00224     stu::Transform transform;
00225     if (tf_manager_.GetTransform(target_frame_, stu::_wgs84_frame, transform))
00226     {
00227       for (size_t i = 0; i < waypoints_.size(); i++)
00228       {
00229         tf::Vector3 waypoint(
00230             waypoints_[i].position.x,
00231             waypoints_[i].position.y,
00232             0.0);
00233         waypoint = transform * waypoint;
00234 
00235         QPointF transformed = map_canvas_->FixedFrameToMapGlCoord(QPointF(waypoint.x(), waypoint.y()));
00236 
00237         double distance = QLineF(transformed, point).length();
00238 
00239         if (distance < closest_distance)
00240         {
00241           closest_distance = distance;
00242           closest_point = static_cast<int>(i);
00243         }
00244       }
00245     }
00246 
00247     if (event->button() == Qt::LeftButton)
00248     {
00249       if (closest_distance < 15)
00250       {
00251         selected_point_ = closest_point;
00252         return true;
00253       }
00254       else
00255       {
00256         is_mouse_down_ = true;
00257 #if QT_VERSION >= 0x050000
00258         mouse_down_pos_ = event->localPos();
00259 #else
00260         mouse_down_pos_ = event->posF();
00261 #endif
00262         mouse_down_time_ = QDateTime::currentMSecsSinceEpoch();
00263         return false;
00264       }
00265     }
00266     else if (event->button() == Qt::RightButton)
00267     {
00268       if (closest_distance < 15)
00269       {
00270         waypoints_.erase(waypoints_.begin() + closest_point);
00271         PlanRoute();
00272         return true;
00273       }
00274     }
00275 
00276     return false;
00277   }
00278 
00279   bool PlanRoutePlugin::handleMouseRelease(QMouseEvent* event)
00280   {
00281 #if QT_VERSION >= 0x050000
00282     QPointF point = event->localPos();
00283 #else
00284     QPointF point = event->posF();
00285 #endif
00286     if (selected_point_ >= 0 && static_cast<size_t>(selected_point_) < waypoints_.size())
00287     {
00288       stu::Transform transform;
00289       if (tf_manager_.GetTransform(stu::_wgs84_frame, target_frame_, transform))
00290       {
00291         QPointF transformed = map_canvas_->MapGlCoordToFixedFrame(point);
00292         tf::Vector3 position(transformed.x(), transformed.y(), 0.0);
00293         position = transform * position;
00294         waypoints_[selected_point_].position.x = position.x();
00295         waypoints_[selected_point_].position.y = position.y();
00296         PlanRoute();
00297       }
00298 
00299       selected_point_ = -1;
00300       return true;
00301     }
00302     else if (is_mouse_down_)
00303     {
00304       qreal distance = QLineF(mouse_down_pos_, point).length();
00305       qint64 msecsDiff = QDateTime::currentMSecsSinceEpoch() - mouse_down_time_;
00306 
00307       // Only fire the event if the mouse has moved less than the maximum distance
00308       // and was held for shorter than the maximum time..  This prevents click
00309       // events from being fired if the user is dragging the mouse across the map
00310       // or just holding the cursor in place.
00311       if (msecsDiff < max_ms_ && distance <= max_distance_)
00312       {
00313         QPointF transformed = map_canvas_->MapGlCoordToFixedFrame(point);
00314 
00315         stu::Transform transform;
00316         tf::Vector3 position(transformed.x(), transformed.y(), 0.0);
00317         if (tf_manager_.GetTransform(stu::_wgs84_frame, target_frame_, transform))
00318         {
00319           position = transform * position;
00320 
00321           geometry_msgs::Pose pose;
00322           pose.position.x = position.x();
00323           pose.position.y = position.y();
00324           waypoints_.push_back(pose);
00325           PlanRoute();
00326         }
00327       }
00328     }
00329     is_mouse_down_ = false;
00330 
00331     return false;
00332   }
00333 
00334   bool PlanRoutePlugin::handleMouseMove(QMouseEvent* event)
00335   {
00336     if (selected_point_ >= 0 && static_cast<size_t>(selected_point_) < waypoints_.size())
00337     {
00338 #if QT_VERSION >= 0x050000
00339       QPointF point = event->localPos();
00340 #else
00341       QPointF point = event->posF();
00342 #endif
00343       stu::Transform transform;
00344       if (tf_manager_.GetTransform(stu::_wgs84_frame, target_frame_, transform))
00345       {
00346         QPointF transformed = map_canvas_->MapGlCoordToFixedFrame(point);
00347         tf::Vector3 position(transformed.x(), transformed.y(), 0.0);
00348         position = transform * position;
00349         waypoints_[selected_point_].position.y = position.y();
00350         waypoints_[selected_point_].position.x = position.x();
00351         PlanRoute();
00352       }
00353 
00354       return true;
00355     }
00356     return false;
00357   }
00358 
00359   void PlanRoutePlugin::Draw(double x, double y, double scale)
00360   {
00361     stu::Transform transform;
00362     if (tf_manager_.GetTransform(target_frame_, stu::_wgs84_frame, transform))
00363     {
00364       if (!failed_service_)
00365       {
00366         if (route_preview_)
00367         {
00368           sru::Route route = *route_preview_;
00369           sru::transform(route, transform, target_frame_);
00370 
00371           glLineWidth(2);
00372           const QColor color = ui_.color->color();
00373           glColor4d(color.redF(), color.greenF(), color.blueF(), 1.0);
00374           glBegin(GL_LINE_STRIP);
00375 
00376           for (size_t i = 0; i < route.points.size(); i++)
00377           {
00378             glVertex2d(route.points[i].position().x(), route.points[i].position().y());
00379           }
00380 
00381           glEnd();
00382         }
00383 
00384         PrintInfo("OK");
00385       }
00386 
00387       // Draw waypoints
00388 
00389       glPointSize(20);
00390       glColor4f(0.0, 1.0, 1.0, 1.0);
00391       glBegin(GL_POINTS);
00392 
00393       for (size_t i = 0; i < waypoints_.size(); i++)
00394       {
00395         tf::Vector3 point(waypoints_[i].position.x, waypoints_[i].position.y, 0);
00396         point = transform * point;
00397         glVertex2d(point.x(), point.y());
00398       }
00399       glEnd();
00400     }
00401     else
00402     {
00403       PrintError("Failed to transform.");
00404     }
00405   }
00406 
00407   void PlanRoutePlugin::Paint(QPainter* painter, double x, double y, double scale)
00408   {
00409     painter->save();
00410     painter->resetTransform();
00411 
00412     QPen pen(QBrush(QColor(Qt::darkCyan).darker()), 1);
00413     painter->setPen(pen);
00414     painter->setFont(QFont("DejaVu Sans Mono", 7));
00415 
00416     stu::Transform transform;
00417     if (tf_manager_.GetTransform(target_frame_, stu::_wgs84_frame, transform))
00418     {
00419       for (size_t i = 0; i < waypoints_.size(); i++)
00420       {
00421         tf::Vector3 point(waypoints_[i].position.x, waypoints_[i].position.y, 0);
00422         point = transform * point;
00423         QPointF gl_point = map_canvas_->FixedFrameToMapGlCoord(QPointF(point.x(), point.y()));
00424         QPointF corner(gl_point.x() - 20, gl_point.y() - 20);
00425         QRectF rect(corner, QSizeF(40, 40));
00426         painter->drawText(rect, Qt::AlignHCenter | Qt::AlignVCenter, QString::fromStdString(boost::lexical_cast<std::string>(i + 1)));
00427       }
00428     }
00429 
00430     painter->restore();
00431   }
00432 
00433   void PlanRoutePlugin::LoadConfig(const YAML::Node& node, const std::string& path)
00434   {
00435     if (node["route_topic"])
00436     {
00437       std::string route_topic;
00438       node["route_topic"] >> route_topic;
00439       ui_.topic->setText(route_topic.c_str());
00440     }
00441     if (node["color"])
00442     {
00443       std::string color;
00444       node["color"] >> color;
00445       ui_.color->setColor(QColor(color.c_str()));
00446     }
00447     if (node["service"])
00448     {
00449       std::string service;
00450       node["service"] >> service;
00451       ui_.service->setText(service.c_str());
00452     }
00453     if (node["start_from_vehicle"])
00454     {
00455       bool start_from_vehicle;
00456       node["start_from_vehicle"] >> start_from_vehicle;
00457       ui_.start_from_vehicle->setChecked(start_from_vehicle);
00458     }
00459 
00460     PlanRoute();
00461   }
00462 
00463   void PlanRoutePlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path)
00464   {
00465     std::string route_topic = ui_.topic->text().toStdString();
00466     emitter << YAML::Key << "route_topic" << YAML::Value << route_topic;
00467 
00468     std::string color = ui_.color->color().name().toStdString();
00469     emitter << YAML::Key << "color" << YAML::Value << color;
00470 
00471     std::string service = ui_.service->text().toStdString();
00472     emitter << YAML::Key << "service" << YAML::Value << service;
00473 
00474     bool start_from_vehicle = ui_.start_from_vehicle->isChecked();
00475     emitter << YAML::Key << "start_from_vehicle" << YAML::Value << start_from_vehicle;
00476   }
00477 }


mapviz_plugins
Author(s): Marc Alban
autogenerated on Thu Jun 6 2019 18:51:07