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


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