odometry_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/odometry_plugin.h>
00031 
00032 // C++ standard libraries
00033 #include <cstdio>
00034 #include <vector>
00035 
00036 // QT libraries
00037 #include <QDialog>
00038 #include <QGLWidget>
00039 #include <QPainter>
00040 #include <QPalette>
00041 
00042 #include <opencv2/core/core.hpp>
00043 
00044 // ROS libraries
00045 #include <ros/master.h>
00046 
00047 #include <swri_image_util/geometry_util.h>
00048 #include <swri_transform_util/transform_util.h>
00049 #include <mapviz/select_topic_dialog.h>
00050 
00051 // Declare plugin
00052 #include <pluginlib/class_list_macros.h>
00053 PLUGINLIB_EXPORT_CLASS(mapviz_plugins::OdometryPlugin, mapviz::MapvizPlugin)
00054 
00055 namespace mapviz_plugins
00056 {
00057   OdometryPlugin::OdometryPlugin() : config_widget_(new QWidget())
00058   {
00059     ui_.setupUi(config_widget_);
00060     covariance_checked_ = ui_.show_covariance->isChecked();
00061     ui_.color->setColor(Qt::green);
00062 
00063     // Set background white
00064     QPalette p(config_widget_->palette());
00065     p.setColor(QPalette::Background, Qt::white);
00066     config_widget_->setPalette(p);
00067 
00068     // Set status text red
00069     QPalette p3(ui_.status->palette());
00070     p3.setColor(QPalette::Text, Qt::red);
00071     ui_.status->setPalette(p3);
00072 
00073     QObject::connect(ui_.show_timestamps, SIGNAL(valueChanged(int)), this,
00074                      SLOT(TopicEditor()));
00075     QObject::connect(ui_.selecttopic, SIGNAL(clicked()), this,
00076                      SLOT(SelectTopic()));
00077     QObject::connect(ui_.topic, SIGNAL(editingFinished()), this,
00078                      SLOT(TopicEdited()));
00079     QObject::connect(ui_.positiontolerance, SIGNAL(valueChanged(double)), this,
00080                      SLOT(PositionToleranceChanged(double)));
00081     QObject::connect(ui_.buffersize, SIGNAL(valueChanged(int)), this,
00082                      SLOT(BufferSizeChanged(int)));
00083     QObject::connect(ui_.drawstyle, SIGNAL(activated(QString)), this,
00084                      SLOT(SetDrawStyle(QString)));
00085     QObject::connect(ui_.static_arrow_sizes, SIGNAL(clicked(bool)),
00086                      this, SLOT(SetStaticArrowSizes(bool)));
00087     QObject::connect(ui_.arrow_size, SIGNAL(valueChanged(int)),
00088                      this, SLOT(SetArrowSize(int)));
00089     connect(ui_.color, SIGNAL(colorEdited(const QColor&)), this,
00090             SLOT(SetColor(const QColor&)));
00091   }
00092 
00093   OdometryPlugin::~OdometryPlugin()
00094   {
00095   }
00096 
00097   void OdometryPlugin::SelectTopic()
00098   {
00099     ros::master::TopicInfo topic =
00100         mapviz::SelectTopicDialog::selectTopic("nav_msgs/Odometry");
00101 
00102     if (!topic.name.empty())
00103     {
00104       ui_.topic->setText(QString::fromStdString(topic.name));
00105       TopicEdited();
00106     }
00107   }
00108 
00109   void OdometryPlugin::TopicEdited()
00110   {
00111     std::string topic = ui_.topic->text().trimmed().toStdString();
00112     if (topic != topic_)
00113     {
00114       initialized_ = false;
00115       points_.clear();
00116       has_message_ = false;
00117       PrintWarning("No messages received.");
00118 
00119       odometry_sub_.shutdown();
00120 
00121       topic_ = topic;
00122       if (!topic.empty())
00123       {
00124         odometry_sub_ = node_.subscribe(
00125                     topic_, 1, &OdometryPlugin::odometryCallback, this);
00126 
00127         ROS_INFO("Subscribing to %s", topic_.c_str());
00128       }
00129     }
00130   }
00131 
00132   void OdometryPlugin::odometryCallback(
00133       const nav_msgs::OdometryConstPtr odometry)
00134   {
00135     if (!has_message_)
00136     {
00137       initialized_ = true;
00138       has_message_ = true;
00139     }
00140 
00141     // Note that unlike some plugins, this one does not store nor rely on the
00142     // source_frame_ member variable.  This one can potentially store many
00143     // messages with different source frames, so we need to store and transform
00144     // them individually.
00145     StampedPoint stamped_point;
00146     stamped_point.stamp = odometry->header.stamp;
00147     stamped_point.source_frame = odometry->header.frame_id;
00148 
00149     stamped_point.point = tf::Point(odometry->pose.pose.position.x,
00150                                     odometry->pose.pose.position.y,
00151                                     odometry->pose.pose.position.z);
00152 
00153     stamped_point.orientation = tf::Quaternion(
00154         odometry->pose.pose.orientation.x,
00155         odometry->pose.pose.orientation.y,
00156         odometry->pose.pose.orientation.z,
00157         odometry->pose.pose.orientation.w);
00158 
00159     if (points_.empty() ||
00160         stamped_point.point.distance(points_.back().point) >=
00161             position_tolerance_)
00162     {
00163       points_.push_back(stamped_point);
00164     }
00165 
00166     if (buffer_size_ > 0)
00167     {
00168       while (static_cast<int>(points_.size()) > buffer_size_)
00169       {
00170         points_.pop_front();
00171       }
00172     }
00173 
00174     cur_point_ = stamped_point;
00175     covariance_checked_ = ui_.show_covariance->isChecked();
00176     lap_checked_ = ui_.show_laps->isChecked();
00177 
00178     if (covariance_checked_)
00179     {
00180       tf::Matrix3x3 tf_cov =
00181           swri_transform_util::GetUpperLeft(odometry->pose.covariance);
00182 
00183       if (tf_cov[0][0] < 100000 && tf_cov[1][1] < 100000)
00184       {
00185         cv::Mat cov_matrix_3d(3, 3, CV_32FC1);
00186         for (int32_t r = 0; r < 3; r++)
00187         {
00188           for (int32_t c = 0; c < 3; c++)
00189           {
00190             cov_matrix_3d.at<float>(r, c) = tf_cov[r][c];
00191           }
00192         }
00193 
00194         cv::Mat cov_matrix_2d =
00195             swri_image_util::ProjectEllipsoid(cov_matrix_3d);
00196 
00197         if (!cov_matrix_2d.empty())
00198         {
00199           cur_point_.cov_points = swri_image_util::GetEllipsePoints(
00200               cov_matrix_2d, cur_point_.point, 3, 32);
00201 
00202           cur_point_.transformed_cov_points = cur_point_.cov_points;
00203         }
00204         else
00205         {
00206           ROS_ERROR("Failed to project x, y, z covariance to xy-plane.");
00207         }
00208       }
00209     }
00210   }
00211 
00212   void OdometryPlugin::PrintError(const std::string& message)
00213   {
00214     PrintErrorHelper(ui_.status, message);
00215   }
00216 
00217   void OdometryPlugin::PrintInfo(const std::string& message)
00218   {
00219     PrintInfoHelper(ui_.status, message);
00220   }
00221 
00222   void OdometryPlugin::PrintWarning(const std::string& message)
00223   {
00224     PrintWarningHelper(ui_.status, message);
00225   }
00226 
00227   QWidget* OdometryPlugin::GetConfigWidget(QWidget* parent)
00228   {
00229     config_widget_->setParent(parent);
00230 
00231     return config_widget_;
00232   }
00233 
00234   bool OdometryPlugin::Initialize(QGLWidget* canvas)
00235   {
00236     canvas_ = canvas;
00237     SetColor(ui_.color->color());
00238 
00239     return true;
00240   }
00241 
00242   void OdometryPlugin::Draw(double x, double y, double scale)
00243   {
00244     if (ui_.show_covariance->isChecked())
00245     {
00246       DrawCovariance();
00247     }
00248     if (DrawPoints(scale))
00249     {
00250       PrintInfo("OK");
00251     }
00252   }
00253   
00254 
00255   void OdometryPlugin::Paint(QPainter* painter, double x, double y, double scale)
00256   {
00257     //dont render any timestamps if the show_timestamps is set to 0
00258     int interval = ui_.show_timestamps->value();
00259     if (interval == 0)
00260     {
00261       return;
00262     }
00263 
00264     QTransform tf = painter->worldTransform();
00265     QFont font("Helvetica", 10);
00266     painter->setFont(font);
00267     painter->save();
00268     painter->resetTransform();
00269 
00270     //set the draw color for the text to be the same as the rest
00271     QPen pen(QBrush(ui_.color->color()), 1);
00272     painter->setPen(pen);
00273 
00274     std::list<StampedPoint>::iterator it = points_.begin();
00275     int counter = 0;//used to alternate between rendering text on some points
00276     for (; it != points_.end(); ++it)
00277     {
00278       if (it->transformed && counter % interval == 0)//this renders a timestamp every 'interval' points
00279       {
00280         QPointF point = tf.map(QPointF(it->transformed_point.getX(),
00281                                        it->transformed_point.getY()));
00282         QString time;
00283         time.setNum(it->stamp.toSec(), 'g', 12);
00284         painter->drawText(point, time);
00285       }
00286       counter++;
00287     }
00288 
00289     painter->restore();
00290   }
00291 
00292   void OdometryPlugin::DrawCovariance()
00293   {
00294     glLineWidth(4);
00295 
00296     glColor4d(color_.redF(), color_.greenF(), color_.blueF(), 1.0);
00297 
00298     if (cur_point_.transformed && !cur_point_.transformed_cov_points.empty())
00299     {
00300       glBegin(GL_LINE_STRIP);
00301 
00302       for (uint32_t i = 0; i < cur_point_.transformed_cov_points.size(); i++)
00303       {
00304         glVertex2d(cur_point_.transformed_cov_points[i].getX(),
00305                    cur_point_.transformed_cov_points[i].getY());
00306       }
00307 
00308       glVertex2d(cur_point_.transformed_cov_points.front().getX(),
00309                  cur_point_.transformed_cov_points.front().getY());
00310 
00311       glEnd();
00312     }
00313   }
00314 
00315   void OdometryPlugin::LoadConfig(const YAML::Node& node,
00316                                   const std::string& path)
00317   {
00318     if (node["topic"])
00319     {
00320       std::string topic;
00321       node["topic"] >> topic;
00322       ui_.topic->setText(topic.c_str());
00323     }
00324 
00325     if (node["color"])
00326     {
00327       std::string color;
00328       node["color"] >> color;
00329       SetColor(QColor(color.c_str()));
00330       ui_.color->setColor(color_);
00331     }
00332 
00333     if (node["draw_style"])
00334     {
00335       std::string draw_style;
00336       node["draw_style"] >> draw_style;
00337 
00338       if (draw_style == "lines")
00339       {
00340         draw_style_ = LINES;
00341         ui_.drawstyle->setCurrentIndex(0);
00342       }
00343       else if (draw_style == "points")
00344       {
00345         draw_style_ = POINTS;
00346         ui_.drawstyle->setCurrentIndex(1);
00347       }
00348       else if (draw_style == "arrows")
00349       {
00350         draw_style_ = ARROWS;
00351         ui_.drawstyle->setCurrentIndex(2);
00352       }
00353     }
00354 
00355     if (node["position_tolerance"])
00356     {
00357       node["position_tolerance"] >> position_tolerance_;
00358       ui_.positiontolerance->setValue(position_tolerance_);
00359     }
00360 
00361     if (node["buffer_size"])
00362     {
00363       node["buffer_size"] >> buffer_size_;
00364       ui_.buffersize->setValue(buffer_size_);
00365     }
00366 
00367     if (node["show_covariance"])
00368     {
00369       bool show_covariance = false;
00370       node["show_covariance"] >> show_covariance;
00371       ui_.show_covariance->setChecked(show_covariance);
00372     }
00373     if (node["show_laps"])
00374     {
00375       bool show_laps = false;
00376       node["show_laps"] >> show_laps;
00377       ui_.show_laps->setChecked(show_laps);
00378     }
00379 
00380     if (node["static_arrow_sizes"])
00381     {
00382       bool static_arrow_sizes = node["static_arrow_sizes"].as<bool>();
00383       ui_.static_arrow_sizes->setChecked(static_arrow_sizes);
00384       SetStaticArrowSizes(static_arrow_sizes);
00385     }
00386 
00387     if (node["arrow_size"])
00388     {
00389       ui_.arrow_size->setValue(node["arrow_size"].as<int>());
00390     }
00391 
00392     if (node["show_timestamps"])
00393     {
00394       ui_.show_timestamps->setValue(node["show_timestamps"].as<int>());
00395     }
00396 
00397     TopicEdited();
00398   }
00399 
00400   void OdometryPlugin::SaveConfig(YAML::Emitter& emitter,
00401                                   const std::string& path)
00402   {
00403     std::string topic = ui_.topic->text().toStdString();
00404     emitter << YAML::Key << "topic" << YAML::Value << topic;
00405 
00406     std::string color = ui_.color->color().name().toStdString();
00407     emitter << YAML::Key << "color" << YAML::Value << color;
00408 
00409     std::string draw_style = ui_.drawstyle->currentText().toStdString();
00410     emitter << YAML::Key << "draw_style" << YAML::Value << draw_style;
00411 
00412     emitter << YAML::Key << "position_tolerance" <<
00413                YAML::Value << position_tolerance_;
00414     if (!lap_checked_)
00415     {
00416       emitter << YAML::Key << "buffer_size" << YAML::Value << buffer_size_;
00417     }
00418     else
00419     {
00420       emitter << YAML::Key << "buffer_size" << YAML::Value << buffer_holder_;
00421     }
00422     bool show_laps = ui_.show_laps->isChecked();
00423     emitter << YAML::Key << "show_laps" << YAML::Value << show_laps;
00424 
00425     bool show_covariance = ui_.show_covariance->isChecked();
00426     emitter << YAML::Key << "show_covariance" << YAML::Value << show_covariance;
00427 
00428     emitter << YAML::Key << "static_arrow_sizes" << YAML::Value << ui_.static_arrow_sizes->isChecked();
00429 
00430     emitter << YAML::Key << "arrow_size" << YAML::Value << ui_.arrow_size->value();
00431 
00432     emitter << YAML::Key << "show_timestamps" << YAML::Value << ui_.show_timestamps->value();
00433   }
00434 }
00435 


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