pointcloud2_plugin.cpp
Go to the documentation of this file.
00001 // *****************************************************************************
00002 //
00003 // Copyright (c) 2015, 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/pointcloud2_plugin.h>
00031 
00032 // C++ standard libraries
00033 #include <cmath>
00034 #include <cstdio>
00035 #include <algorithm>
00036 #include <vector>
00037 #include <map>
00038 
00039 // Boost libraries
00040 #include <boost/algorithm/string.hpp>
00041 
00042 // QT libraries
00043 #include <QColorDialog>
00044 #include <QDialog>
00045 #include <QGLWidget>
00046 
00047 // OpenGL
00048 #include <GL/glew.h>
00049 
00050 // QT Autogenerated
00051 #include "ui_topic_select.h"
00052 
00053 // ROS libraries
00054 #include <ros/master.h>
00055 #include <swri_transform_util/transform.h>
00056 #include <swri_yaml_util/yaml_util.h>
00057 
00058 #include <mapviz/select_topic_dialog.h>
00059 
00060 // Declare plugin
00061 #include <pluginlib/class_list_macros.h>
00062 
00063 PLUGINLIB_DECLARE_CLASS(
00064     mapviz_plugins,
00065     PointCloud2,
00066     mapviz_plugins::PointCloud2Plugin,
00067     mapviz::MapvizPlugin)
00068 
00069 namespace mapviz_plugins
00070 {
00071   PointCloud2Plugin::PointCloud2Plugin() :
00072       config_widget_(new QWidget()),
00073       topic_(""),
00074       alpha_(1.0),
00075       min_value_(0.0),
00076       max_value_(100.0),
00077       point_size_(3),
00078       buffer_size_(1),
00079       new_topic_(true),
00080       has_message_(false),
00081       num_of_feats_(0),
00082       need_new_list_(true),
00083       need_minmax_(false)
00084   {
00085     ui_.setupUi(config_widget_);
00086 
00087     // Set background white
00088     QPalette p(config_widget_->palette());
00089     p.setColor(QPalette::Background, Qt::white);
00090     config_widget_->setPalette(p);
00091 
00092     // Set status text red
00093     QPalette p3(ui_.status->palette());
00094     p3.setColor(QPalette::Text, Qt::red);
00095     ui_.status->setPalette(p3);
00096 
00097     // Initialize color selector colors
00098     ui_.min_color->setColor(Qt::white);
00099     ui_.max_color->setColor(Qt::black);
00100     // Set color transformer choices
00101     ui_.color_transformer->addItem(QString("Flat Color"), QVariant(0));
00102 
00103     QObject::connect(ui_.selecttopic,
00104                      SIGNAL(clicked()),
00105                      this,
00106                      SLOT(SelectTopic()));
00107     QObject::connect(ui_.topic,
00108                      SIGNAL(editingFinished()),
00109                      this,
00110                      SLOT(TopicEdited()));
00111     QObject::connect(ui_.alpha,
00112                      SIGNAL(editingFinished()),
00113                      this,
00114                      SLOT(AlphaEdited()));
00115     QObject::connect(ui_.color_transformer,
00116                      SIGNAL(currentIndexChanged(int)),
00117                      this,
00118                      SLOT(ColorTransformerChanged(int)));
00119     QObject::connect(ui_.max_color,
00120                      SIGNAL(colorEdited(
00121                                 const QColor &)),
00122                      this,
00123                      SLOT(UpdateColors()));
00124     QObject::connect(ui_.min_color,
00125                      SIGNAL(colorEdited(
00126                                 const QColor &)),
00127                      this,
00128                      SLOT(UpdateColors()));
00129     QObject::connect(ui_.minValue,
00130                      SIGNAL(valueChanged(double)),
00131                      this,
00132                      SLOT(MinValueChanged(double)));
00133     QObject::connect(ui_.maxValue,
00134                      SIGNAL(valueChanged(double)),
00135                      this,
00136                      SLOT(MaxValueChanged(double)));
00137     QObject::connect(ui_.bufferSize,
00138                      SIGNAL(valueChanged(int)),
00139                      this,
00140                      SLOT(BufferSizeChanged(int)));
00141     QObject::connect(ui_.pointSize,
00142                      SIGNAL(valueChanged(int)),
00143                      this,
00144                      SLOT(PointSizeChanged(int)));
00145     QObject::connect(ui_.use_rainbow,
00146                      SIGNAL(stateChanged(int)),
00147                      this,
00148                      SLOT(UseRainbowChanged(int)));
00149     QObject::connect(ui_.use_automaxmin,
00150                      SIGNAL(stateChanged(int)),
00151                      this,
00152                      SLOT(UseAutomaxminChanged(int)));
00153     QObject::connect(ui_.max_color,
00154                      SIGNAL(colorEdited(
00155                                 const QColor &)),
00156                      this,
00157                      SLOT(DrawIcon()));
00158     QObject::connect(ui_.min_color,
00159                      SIGNAL(colorEdited(
00160                                 const QColor &)),
00161                      this,
00162                      SLOT(DrawIcon()));
00163     QObject::connect(this,
00164                      SIGNAL(TargetFrameChanged(const std::string&)),
00165                      this,
00166                      SLOT(ResetTransformedPointClouds()));
00167 
00168     PrintInfo("Constructed PointCloud2Plugin");
00169   }
00170 
00171   PointCloud2Plugin::~PointCloud2Plugin()
00172   {
00173   }
00174 
00175   void PointCloud2Plugin::DrawIcon()
00176   {
00177     if (icon_)
00178     {
00179       QPixmap icon(16, 16);
00180       icon.fill(Qt::transparent);
00181 
00182       QPainter painter(&icon);
00183       painter.setRenderHint(QPainter::Antialiasing, true);
00184 
00185       QPen pen;
00186       pen.setWidth(4);
00187       pen.setCapStyle(Qt::RoundCap);
00188 
00189       pen.setColor(ui_.min_color->color());
00190       painter.setPen(pen);
00191       painter.drawPoint(2, 13);
00192 
00193       pen.setColor(ui_.min_color->color());
00194       painter.setPen(pen);
00195       painter.drawPoint(4, 6);
00196 
00197       pen.setColor(ui_.max_color->color());
00198       painter.setPen(pen);
00199       painter.drawPoint(12, 9);
00200 
00201       pen.setColor(ui_.max_color->color());
00202       painter.setPen(pen);
00203       painter.drawPoint(13, 2);
00204 
00205       icon_->SetPixmap(icon);
00206     }
00207   }
00208 
00209   void PointCloud2Plugin::ResetTransformedPointClouds()
00210   {
00211     std::deque<Scan>::iterator scan_it = scans_.begin();
00212     for (; scan_it != scans_.end(); ++scan_it)
00213     {
00214       scan_it->transformed = false;
00215     }
00216   }
00217 
00218   QColor PointCloud2Plugin::CalculateColor(const StampedPoint& point)
00219   {
00220     double val;
00221     unsigned int color_transformer = static_cast<unsigned int>(ui_.color_transformer->currentIndex());
00222     if (num_of_feats_ > 0 && color_transformer > 0)
00223     {
00224       val = point.features[color_transformer - 1];
00225       if (need_minmax_)
00226       {
00227         if (val > max_[color_transformer - 1])
00228         {
00229           max_[color_transformer - 1] = val;
00230         }
00231 
00232         if (val < min_[color_transformer - 1])
00233         {
00234           min_[color_transformer - 1] = val;
00235         }
00236       }
00237     }
00238     else  // No intensity or  (color_transformer == COLOR_FLAT)
00239     {
00240       return ui_.min_color->color();
00241     }
00242 
00243     if (max_value_ > min_value_)
00244     {
00245       val = (val - min_value_) / (max_value_ - min_value_);
00246     }
00247     val = std::max(0.0, std::min(val, 1.0));
00248 
00249     if (ui_.use_automaxmin->isChecked())
00250     {
00251       max_value_ = max_[ui_.color_transformer->currentIndex() - 1];
00252       min_value_ = min_[ui_.color_transformer->currentIndex() - 1];
00253 
00254     }
00255 
00256     if (ui_.use_rainbow->isChecked())
00257     {  // Hue Interpolation
00258 
00259       int hue = (int)(val * 255.0);
00260       return QColor::fromHsl(hue, 255, 127, 255);
00261     }
00262     else
00263     {
00264       const QColor min_color = ui_.min_color->color();
00265       const QColor max_color = ui_.max_color->color();
00266       // RGB Interpolation
00267       int red, green, blue;
00268       red = (int)(val * max_color.red() + ((1.0 - val) * min_color.red()));
00269       green = (int)(val * max_color.green() + ((1.0 - val) * min_color.green()));
00270       blue = (int)(val * max_color.blue() + ((1.0 - val) * min_color.blue()));
00271       return QColor(red, green, blue, 255);
00272     }
00273   }
00274 
00275   inline int32_t findChannelIndex(const sensor_msgs::PointCloud2ConstPtr& cloud, const std::string& channel)
00276   {
00277     for (int32_t i = 0; static_cast<size_t>(i) < cloud->fields.size(); ++i)
00278     {
00279       if (cloud->fields[i].name == channel)
00280       {
00281         return i;
00282       }
00283     }
00284 
00285     return -1;
00286   }
00287 
00288   void PointCloud2Plugin::UpdateColors()
00289   {
00290     {
00291       QMutexLocker locker(&scan_mutex_);
00292       std::deque<Scan>::iterator scan_it = scans_.begin();
00293       for (; scan_it != scans_.end(); ++scan_it)
00294       {
00295         std::deque<StampedPoint>::iterator point_it = scan_it->points.begin();
00296         for (; point_it != scan_it->points.end(); point_it++)
00297         {
00298           point_it->color = CalculateColor(*point_it);
00299         }
00300       }
00301     }
00302     canvas_->update();
00303   }
00304 
00305   void PointCloud2Plugin::SelectTopic()
00306   {
00307     ros::master::TopicInfo topic = mapviz::SelectTopicDialog::selectTopic(
00308         "sensor_msgs/PointCloud2");
00309 
00310     if (!topic.name.empty())
00311     {
00312       ui_.topic->setText(QString::fromStdString(topic.name));
00313       TopicEdited();
00314     }
00315   }
00316 
00317 
00318   void PointCloud2Plugin::TopicEdited()
00319   {
00320     std::string topic = ui_.topic->text().trimmed().toStdString();
00321     if (topic != topic_)
00322     {
00323       initialized_ = false;
00324       {
00325         QMutexLocker locker(&scan_mutex_);
00326         scans_.clear();
00327       }
00328       has_message_ = false;
00329       PrintWarning("No messages received.");
00330 
00331       pc2_sub_.shutdown();
00332 
00333       topic_ = topic;
00334       if (!topic.empty())
00335       {
00336         pc2_sub_ = node_.subscribe(topic_,
00337                                    100,
00338                                    &PointCloud2Plugin::PointCloud2Callback,
00339                                    this);
00340         new_topic_ = true;
00341         need_new_list_ = true;
00342         max_.clear();
00343         min_.clear();
00344         ROS_INFO("Subscribing to %s", topic_.c_str());
00345       }
00346     }
00347   }
00348 
00349   void PointCloud2Plugin::MinValueChanged(double value)
00350   {
00351     min_value_ = value;
00352     UpdateColors();
00353   }
00354 
00355   void PointCloud2Plugin::MaxValueChanged(double value)
00356   {
00357     max_value_ = value;
00358     UpdateColors();
00359   }
00360 
00361   void PointCloud2Plugin::BufferSizeChanged(int value)
00362   {
00363     buffer_size_ = (size_t)value;
00364 
00365     if (buffer_size_ > 0)
00366     {
00367       QMutexLocker locker(&scan_mutex_);
00368       while (scans_.size() > buffer_size_)
00369       {
00370         scans_.pop_front();
00371       }
00372     }
00373 
00374     canvas_->update();
00375   }
00376 
00377   void PointCloud2Plugin::PointSizeChanged(int value)
00378   {
00379     point_size_ = (size_t)value;
00380 
00381     canvas_->update();
00382   }
00383 
00384   void PointCloud2Plugin::PointCloud2Callback(const sensor_msgs::PointCloud2ConstPtr& msg)
00385   {
00386     if (!has_message_)
00387     {
00388       initialized_ = true;
00389       has_message_ = true;
00390     }
00391 
00392     // Note that unlike some plugins, this one does not store nor rely on the
00393     // source_frame_ member variable.  This one can potentially store many
00394     // messages with different source frames, so we need to store and transform
00395     // them individually.
00396 
00397     Scan scan;
00398     scan.stamp = msg->header.stamp;
00399     scan.color = QColor::fromRgbF(1.0f, 0.0f, 0.0f, 1.0f);
00400     scan.source_frame = msg->header.frame_id;
00401     scan.transformed = true;
00402     scan.points.clear();
00403 
00404     swri_transform_util::Transform transform;
00405     if (!GetTransform(scan.source_frame, msg->header.stamp, transform))
00406     {
00407       scan.transformed = false;
00408       PrintError("No transform between " + scan.source_frame + " and " + target_frame_);
00409     }
00410 
00411 
00412     int32_t xi = findChannelIndex(msg, "x");
00413     int32_t yi = findChannelIndex(msg, "y");
00414     int32_t zi = findChannelIndex(msg, "z");
00415 
00416     if (xi == -1 || yi == -1 || zi == -1)
00417     {
00418       return;
00419     }
00420 
00421     if (new_topic_)
00422     {
00423 
00424       for (size_t i = 0; i < msg->fields.size(); ++i)
00425       {
00426         FieldInfo input;
00427         std::string name = msg->fields[i].name;
00428 
00429         uint32_t offset_value = msg->fields[i].offset;
00430         uint8_t datatype_value = msg->fields[i].datatype;
00431         input.offset = offset_value;
00432         input.datatype = datatype_value;
00433         scan.new_features.insert(std::pair<std::string, FieldInfo>(name, input));
00434 
00435       }
00436 
00437       new_topic_ = false;
00438       num_of_feats_ = scan.new_features.size();
00439 
00440       max_.resize(num_of_feats_);
00441       min_.resize(num_of_feats_);
00442 
00443       int label = 1;
00444       if (need_new_list_)
00445       {
00446         int new_feature_index = ui_.color_transformer->currentIndex();
00447         std::map<std::string, FieldInfo>::const_iterator it;
00448         for (it = scan.new_features.begin(); it != scan.new_features.end(); ++it)
00449         {
00450           ui_.color_transformer->removeItem(static_cast<int>(num_of_feats_));
00451           num_of_feats_--;
00452 
00453         }
00454 
00455         for (it = scan.new_features.begin(); it != scan.new_features.end(); ++it)
00456         {
00457           std::string const field = it->first;
00458           if (field == saved_color_transformer_)
00459           {
00460             // The very first time we see a new set of features, that means the
00461             // plugin was just created; if we have a saved value, set the current
00462             // index to that and clear the saved value.
00463             new_feature_index = label;
00464             saved_color_transformer_ = "";
00465           }
00466 
00467           ui_.color_transformer->addItem(QString::fromStdString(field), QVariant(label));
00468           num_of_feats_++;
00469           label++;
00470 
00471         }
00472         ui_.color_transformer->setCurrentIndex(new_feature_index);
00473         need_new_list_ = false;
00474       }
00475     }
00476 
00477     if (!msg->data.empty())
00478     {
00479       const uint8_t* ptr = &msg->data.front();
00480       const uint8_t* ptr_end = &msg->data.back();
00481       const uint32_t point_step = msg->point_step;
00482       const uint32_t xoff = msg->fields[xi].offset;
00483       const uint32_t yoff = msg->fields[yi].offset;
00484       const uint32_t zoff = msg->fields[zi].offset;
00485       for (; ptr < ptr_end; ptr += point_step)
00486       {
00487         float x = *reinterpret_cast<const float*>(ptr + xoff);
00488         float y = *reinterpret_cast<const float*>(ptr + yoff);
00489         float z = *reinterpret_cast<const float*>(ptr + zoff);
00490 
00491         StampedPoint point;
00492         point.point = tf::Point(x, y, z);
00493         point.features.resize(scan.new_features.size());
00494         int count = 0;
00495         std::map<std::string, FieldInfo>::const_iterator it;
00496         for (it = scan.new_features.begin(); it != scan.new_features.end(); ++it)
00497         {
00498           point.features[count] = PointFeature(ptr, (it->second));
00499           count++;
00500         }
00501 
00502         if (scan.transformed)
00503         {
00504           point.transformed_point = transform * point.point;
00505         }
00506 
00507         point.color = CalculateColor(point);
00508 
00509         scan.points.push_back(point);
00510       }
00511     }
00512 
00513     {
00514       QMutexLocker locker(&scan_mutex_);
00515       scans_.push_back(scan);
00516       if (buffer_size_ > 0)
00517       {
00518         while (scans_.size() > buffer_size_)
00519         {
00520           scans_.pop_front();
00521         }
00522       }
00523     }
00524     new_topic_ = true;
00525     canvas_->update();
00526   }
00527 
00528   double PointCloud2Plugin::PointFeature(const uint8_t* data, const FieldInfo& feature_info)
00529   {
00530     switch (feature_info.datatype)
00531     {
00532       case 1:
00533         return *reinterpret_cast<const int8_t*>(data + feature_info.offset);
00534       case 2:
00535         return *(data + feature_info.offset);
00536       case 3:
00537         return *reinterpret_cast<const int16_t*>(data + feature_info.offset);
00538       case 4:
00539         return *reinterpret_cast<const uint16_t*>(data + feature_info.offset);
00540       case 5:
00541         return *reinterpret_cast<const int32_t*>(data + feature_info.offset);
00542       case 6:
00543         return *reinterpret_cast<const uint32_t*>(data + feature_info.offset);
00544       case 7:
00545         return *reinterpret_cast<const float*>(data + feature_info.offset);
00546       case 8:
00547         return *reinterpret_cast<const double*>(data + feature_info.offset);
00548       default:
00549         ROS_WARN("Unknown data type in point: %d", feature_info.datatype);
00550         return 0.0;
00551     }
00552   }
00553 
00554   void PointCloud2Plugin::PrintError(const std::string& message)
00555   {
00556     if (message == ui_.status->text().toStdString())
00557     {
00558       return;
00559     }
00560 
00561     ROS_ERROR("Error: %s", message.c_str());
00562     QPalette p(ui_.status->palette());
00563     p.setColor(QPalette::Text, Qt::red);
00564     ui_.status->setPalette(p);
00565     ui_.status->setText(message.c_str());
00566   }
00567 
00568   void PointCloud2Plugin::PrintInfo(const std::string& message)
00569   {
00570     if (message == ui_.status->text().toStdString())
00571     {
00572       return;
00573     }
00574 
00575     ROS_INFO("%s", message.c_str());
00576     QPalette p(ui_.status->palette());
00577     p.setColor(QPalette::Text, Qt::green);
00578     ui_.status->setPalette(p);
00579     ui_.status->setText(message.c_str());
00580   }
00581 
00582   void PointCloud2Plugin::PrintWarning(const std::string& message)
00583   {
00584     if (message == ui_.status->text().toStdString())
00585     {
00586       return;
00587     }
00588 
00589     ROS_WARN("%s", message.c_str());
00590     QPalette p(ui_.status->palette());
00591     p.setColor(QPalette::Text, Qt::darkYellow);
00592     ui_.status->setPalette(p);
00593     ui_.status->setText(message.c_str());
00594   }
00595 
00596   QWidget* PointCloud2Plugin::GetConfigWidget(QWidget* parent)
00597   {
00598     config_widget_->setParent(parent);
00599 
00600     return config_widget_;
00601   }
00602 
00603   bool PointCloud2Plugin::Initialize(QGLWidget* canvas)
00604   {
00605     canvas_ = canvas;
00606 
00607     DrawIcon();
00608 
00609     return true;
00610   }
00611 
00612   void PointCloud2Plugin::Draw(double x, double y, double scale)
00613   {
00614     glPointSize(point_size_);
00615     glBegin(GL_POINTS);
00616 
00617     std::deque<Scan>::const_iterator scan_it;
00618     std::deque<StampedPoint>::const_iterator point_it;
00619     {
00620       QMutexLocker locker(&scan_mutex_);
00621 
00622       for (scan_it = scans_.begin(); scan_it != scans_.end(); scan_it++)
00623       {
00624         if (scan_it->transformed)
00625         {
00626           for (point_it = scan_it->points.begin(); point_it != scan_it->points.end(); ++point_it)
00627           {
00628             glColor4d(
00629                 point_it->color.redF(),
00630                 point_it->color.greenF(),
00631                 point_it->color.blueF(),
00632                 alpha_);
00633             glVertex2d(
00634                 point_it->transformed_point.getX(),
00635                 point_it->transformed_point.getY());
00636           }
00637         }
00638       }
00639     }
00640 
00641     glEnd();
00642 
00643     PrintInfo("OK");
00644   }
00645 
00646   void PointCloud2Plugin::UseRainbowChanged(int check_state)
00647   {
00648     UpdateMinMaxWidgets();
00649 
00650     UpdateColors();
00651   }
00652 
00653   void PointCloud2Plugin::UseAutomaxminChanged(int check_state)
00654   {
00655     if (check_state == need_minmax_)
00656     {
00657       need_minmax_ = true;
00658     }
00659 
00660     UpdateMinMaxWidgets();
00661 
00662     UpdateColors();
00663   }
00664 
00665   void PointCloud2Plugin::Transform()
00666   {
00667     {
00668       QMutexLocker locker(&scan_mutex_);
00669 
00670       std::deque<Scan>::iterator scan_it = scans_.begin();
00671       bool was_using_latest_transforms = use_latest_transforms_;
00672       use_latest_transforms_ = false;
00673       for (; scan_it != scans_.end(); ++scan_it)
00674       {
00675         Scan& scan = *scan_it;
00676 
00677         if (!scan_it->transformed)
00678         {
00679           swri_transform_util::Transform transform;
00680           if (GetTransform(scan.source_frame, scan.stamp, transform))
00681           {
00682             scan.transformed = true;
00683             std::deque<StampedPoint>::iterator point_it = scan.points.begin();
00684             for (; point_it != scan.points.end(); ++point_it)
00685             {
00686               point_it->transformed_point = transform * point_it->point;
00687             }
00688           }
00689           else
00690           {
00691             ROS_WARN("Unable to get transform.");
00692             scan.transformed = false;
00693           }
00694         }
00695       }
00696       use_latest_transforms_ = was_using_latest_transforms;
00697     }
00698     // Z color is based on transformed color, so it is dependent on the
00699     // transform
00700     if (ui_.color_transformer->currentIndex() == COLOR_Z)
00701     {
00702       UpdateColors();
00703     }
00704   }
00705 
00706   void PointCloud2Plugin::LoadConfig(const YAML::Node& node,
00707                                      const std::string& path)
00708   {
00709     if (node["topic"])
00710     {
00711       std::string topic;
00712       node["topic"] >> topic;
00713       ui_.topic->setText(boost::trim_copy(topic).c_str());
00714       TopicEdited();
00715     }
00716 
00717     if (node["size"])
00718     {
00719       node["size"] >> point_size_;
00720       ui_.pointSize->setValue(static_cast<int>(point_size_));
00721     }
00722 
00723     if (node["buffer_size"])
00724     {
00725       node["buffer_size"] >> buffer_size_;
00726       ui_.bufferSize->setValue(static_cast<int>(buffer_size_));
00727     }
00728 
00729     if (node["color_transformer"])
00730     {
00731       node["color_transformer"] >> saved_color_transformer_;
00732     }
00733 
00734     if (node["min_color"])
00735     {
00736       std::string min_color_str;
00737       node["min_color"] >> min_color_str;
00738       ui_.min_color->setColor(QColor(min_color_str.c_str()));
00739     }
00740     
00741     if (node["max_color"])
00742     {
00743       std::string max_color_str;
00744       node["max_color"] >> max_color_str;
00745       ui_.max_color->setColor(QColor(max_color_str.c_str()));
00746     }
00747 
00748     if (node["value_min"])
00749     {
00750       node["value_min"] >> min_value_;
00751       ui_.minValue->setValue(min_value_);
00752     }
00753 
00754     if (node["value_max"])
00755     {
00756       node["value_max"] >> max_value_;
00757       ui_.maxValue->setValue(max_value_);
00758     }
00759 
00760     if (node["alpha"])
00761     {      
00762       node["alpha"] >> alpha_;
00763       ui_.alpha->setValue(alpha_);
00764       AlphaEdited();
00765     }
00766 
00767     if (node["use_rainbow"])
00768     {
00769       bool use_rainbow;
00770       node["use_rainbow"] >> use_rainbow;
00771       ui_.use_rainbow->setChecked(use_rainbow);
00772     }
00773     
00774     // UseRainbowChanged must be called *before* ColorTransformerChanged
00775     UseRainbowChanged(ui_.use_rainbow->checkState());
00776 
00777     if (node["use_automaxmin"])
00778     {
00779       bool use_automaxmin;
00780       node["use_automaxmin"] >> use_automaxmin;
00781       ui_.use_automaxmin->setChecked(use_automaxmin);
00782     }
00783     // UseRainbowChanged must be called *before* ColorTransformerChanged
00784     UseAutomaxminChanged(ui_.use_automaxmin->checkState());
00785     // ColorTransformerChanged will also update colors of all points
00786     ColorTransformerChanged(ui_.color_transformer->currentIndex());
00787   }
00788 
00789   void PointCloud2Plugin::ColorTransformerChanged(int index)
00790   {
00791     ROS_DEBUG("Color transformer changed to %d", index);
00792     UpdateMinMaxWidgets();
00793     UpdateColors();
00794   }
00795 
00796   void PointCloud2Plugin::UpdateMinMaxWidgets()
00797   {
00798     bool color_is_flat = ui_.color_transformer->currentIndex() == COLOR_FLAT;
00799 
00800     if (color_is_flat) 
00801     {
00802       ui_.maxColorLabel->hide();
00803       ui_.max_color->hide();
00804       ui_.minColorLabel->hide();
00805       ui_.min_max_color_widget->show();
00806       ui_.min_max_value_widget->hide();
00807       ui_.use_automaxmin->hide();
00808       ui_.use_rainbow->hide();
00809     }
00810     else
00811     {
00812       ui_.maxColorLabel->show();
00813       ui_.max_color->show();
00814       ui_.minColorLabel->show();
00815       ui_.min_max_color_widget->setVisible(!ui_.use_rainbow->isChecked());
00816       ui_.min_max_value_widget->setVisible(!ui_.use_automaxmin->isChecked());
00817       ui_.use_automaxmin->show();
00818       ui_.use_rainbow->show();
00819     }
00820 
00821     config_widget_->updateGeometry();
00822     config_widget_->adjustSize();
00823 
00824     Q_EMIT SizeChanged();
00825   }
00826 
00830   void PointCloud2Plugin::AlphaEdited()
00831   {
00832     alpha_ = std::max(0.0f, std::min(ui_.alpha->text().toFloat(), 1.0f));
00833     ui_.alpha->setValue(alpha_);
00834   }
00835 
00836   void PointCloud2Plugin::SaveConfig(YAML::Emitter& emitter,
00837                                      const std::string& path)
00838   {
00839     emitter << YAML::Key << "topic" <<
00840       YAML::Value << boost::trim_copy(ui_.topic->text().toStdString());
00841     emitter << YAML::Key << "size" <<
00842       YAML::Value << ui_.pointSize->value();
00843     emitter << YAML::Key << "buffer_size" <<
00844       YAML::Value << ui_.bufferSize->value();
00845     emitter << YAML::Key << "alpha" <<
00846       YAML::Value << alpha_;
00847     emitter << YAML::Key << "color_transformer" <<
00848       YAML::Value << ui_.color_transformer->currentText().toStdString();
00849     emitter << YAML::Key << "min_color" <<
00850       YAML::Value << ui_.min_color->color().name().toStdString();
00851     emitter << YAML::Key << "max_color" <<
00852       YAML::Value << ui_.max_color->color().name().toStdString();
00853     emitter << YAML::Key << "value_min" <<
00854       YAML::Value << ui_.minValue->text().toDouble();
00855     emitter << YAML::Key << "value_max" <<
00856       YAML::Value << ui_.maxValue->text().toDouble();
00857     emitter << YAML::Key << "use_rainbow" <<
00858       YAML::Value << ui_.use_rainbow->isChecked();
00859     emitter << YAML::Key << "use_automaxmin" <<
00860       YAML::Value << ui_.use_automaxmin->isChecked();
00861   }
00862 }
00863 
00864 


mapviz_plugins
Author(s): Marc Alban
autogenerated on Thu Aug 24 2017 02:46:09