laserscan_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/laserscan_plugin.h>
00031 
00032 // C++ standard libraries
00033 #include <cmath>
00034 #include <cstdio>
00035 #include <algorithm>
00036 #include <vector>
00037 
00038 // Boost libraries
00039 #include <boost/algorithm/string.hpp>
00040 
00041 // QT libraries
00042 #include <QColorDialog>
00043 #include <QDialog>
00044 #include <QGLWidget>
00045 
00046 // OpenGL
00047 #include <GL/glew.h>
00048 
00049 // QT Autogenerated
00050 #include "ui_topic_select.h"
00051 
00052 // ROS libraries
00053 #include <ros/master.h>
00054 #include <swri_transform_util/transform.h>
00055 #include <swri_yaml_util/yaml_util.h>
00056 
00057 #include <mapviz/select_topic_dialog.h>
00058 
00059 // Declare plugin
00060 #include <pluginlib/class_list_macros.h>
00061 PLUGINLIB_DECLARE_CLASS(
00062     mapviz_plugins,
00063     laserscan,
00064     mapviz_plugins::LaserScanPlugin,
00065     mapviz::MapvizPlugin)
00066 
00067 namespace mapviz_plugins
00068 {
00069   LaserScanPlugin::LaserScanPlugin() :
00070       config_widget_(new QWidget()),
00071           topic_(""),
00072           alpha_(1.0),
00073           min_value_(0.0),
00074           max_value_(100.0),
00075           point_size_(3)
00076   {
00077     ui_.setupUi(config_widget_);
00078 
00079     // Set background white
00080     QPalette p(config_widget_->palette());
00081     p.setColor(QPalette::Background, Qt::white);
00082     config_widget_->setPalette(p);
00083 
00084     // Set status text red
00085     QPalette p3(ui_.status->palette());
00086     p3.setColor(QPalette::Text, Qt::red);
00087     ui_.status->setPalette(p3);
00088 
00089     // Initialize color selector colors
00090     ui_.min_color->setColor(Qt::white);
00091     ui_.max_color->setColor(Qt::black);
00092     
00093     // Set color transformer choices
00094     ui_.color_transformer->addItem(QString("Flat Color"), QVariant(0));
00095     ui_.color_transformer->addItem(QString("Intensity"), QVariant(1));
00096     ui_.color_transformer->addItem(QString("Range"), QVariant(2));
00097     ui_.color_transformer->addItem(QString("X Axis"), QVariant(3));
00098     ui_.color_transformer->addItem(QString("Y Axis"), QVariant(4));
00099     ui_.color_transformer->addItem(QString("Z Axis"), QVariant(5));
00100 
00101     QObject::connect(ui_.selecttopic,
00102         SIGNAL(clicked()),
00103         this,
00104         SLOT(SelectTopic()));
00105     QObject::connect(ui_.topic,
00106         SIGNAL(editingFinished()),
00107         this,
00108         SLOT(TopicEdited()));
00109     QObject::connect(ui_.alpha,
00110         SIGNAL(editingFinished()),
00111         this,
00112         SLOT(AlphaEdited()));
00113     QObject::connect(ui_.color_transformer,
00114         SIGNAL(currentIndexChanged(int)),
00115         this,
00116         SLOT(ColorTransformerChanged(int)));
00117     QObject::connect(ui_.max_color,
00118         SIGNAL(colorEdited(const QColor &)),
00119         this,
00120         SLOT(UpdateColors()));
00121     QObject::connect(ui_.min_color,
00122         SIGNAL(colorEdited(const QColor &)),
00123         this,
00124         SLOT(UpdateColors()));
00125     QObject::connect(ui_.minValue,
00126         SIGNAL(valueChanged(double)),
00127         this,
00128         SLOT(MinValueChanged(double)));
00129     QObject::connect(ui_.maxValue,
00130         SIGNAL(valueChanged(double)),
00131         this,
00132         SLOT(MaxValueChanged(double)));
00133     QObject::connect(ui_.bufferSize,
00134         SIGNAL(valueChanged(int)),
00135         this,
00136         SLOT(BufferSizeChanged(int)));
00137     QObject::connect(ui_.pointSize,
00138         SIGNAL(valueChanged(int)),
00139         this,
00140         SLOT(PointSizeChanged(int)));
00141     QObject::connect(ui_.use_rainbow,
00142         SIGNAL(stateChanged(int)),
00143         this,
00144         SLOT(UseRainbowChanged(int)));
00145 
00146     QObject::connect(ui_.max_color,
00147         SIGNAL(colorEdited(const QColor &)),
00148         this,
00149         SLOT(DrawIcon()));
00150     QObject::connect(ui_.min_color,
00151         SIGNAL(colorEdited(const QColor &)),
00152         this,
00153         SLOT(DrawIcon()));
00154 
00155     PrintInfo("Constructed LaserScanPlugin");
00156   }
00157 
00158   LaserScanPlugin::~LaserScanPlugin()
00159   {
00160   }
00161 
00162   void LaserScanPlugin::DrawIcon()
00163   {
00164     if (icon_)
00165     {
00166       QPixmap icon(16, 16);
00167       icon.fill(Qt::transparent);
00168 
00169       QPainter painter(&icon);
00170       painter.setRenderHint(QPainter::Antialiasing, true);
00171 
00172       QPen pen;
00173       pen.setWidth(4);
00174       pen.setCapStyle(Qt::RoundCap);
00175 
00176       pen.setColor(ui_.min_color->color());
00177       painter.setPen(pen);
00178       painter.drawPoint(2, 13);
00179 
00180       pen.setColor(ui_.min_color->color());
00181       painter.setPen(pen);
00182       painter.drawPoint(4, 6);
00183 
00184       pen.setColor(ui_.max_color->color());
00185       painter.setPen(pen);
00186       painter.drawPoint(12, 9);
00187 
00188       pen.setColor(ui_.max_color->color());
00189       painter.setPen(pen);
00190       painter.drawPoint(13, 2);
00191 
00192       icon_->SetPixmap(icon);
00193     }
00194   }
00195 
00196   QColor LaserScanPlugin::CalculateColor(const StampedPoint& point,
00197       bool has_intensity)
00198   {
00199     double val;
00200     int color_transformer = ui_.color_transformer->currentIndex();
00201     if (color_transformer == COLOR_RANGE)
00202     {
00203       val = point.range;
00204     }
00205     else if (color_transformer == COLOR_INTENSITY && has_intensity)
00206     {
00207       val = point.intensity;
00208     }
00209     else if (color_transformer == COLOR_X)
00210     {
00211       val = point.point.x();
00212     }
00213     else if (color_transformer == COLOR_Y)
00214     {
00215       val = point.point.y();
00216     }
00217     else if (color_transformer == COLOR_Z)
00218     {
00219       val = point.transformed_point.z();
00220     }
00221     else  // No intensity or  (color_transformer == COLOR_FLAT)
00222     {
00223       return ui_.min_color->color();
00224     }
00225     if (max_value_ > min_value_)
00226       val = (val - min_value_) / (max_value_ - min_value_);
00227     val = std::max(0.0, std::min(val, 1.0));
00228     if (ui_.use_rainbow->isChecked())
00229     {
00230       // Hue Interpolation
00231       int hue = static_cast<int>(val * 255);
00232       return QColor::fromHsl(hue, 255, 127, 255);
00233     }
00234     else
00235     {
00236       const QColor min_color = ui_.min_color->color();
00237       const QColor max_color = ui_.max_color->color();
00238       // RGB Interpolation
00239       int red, green, blue;
00240       red = static_cast<int>(val * max_color.red()   + ((1.0 - val) * min_color.red()));
00241       green = static_cast<int>(val * max_color.green() + ((1.0 - val) * min_color.green()));
00242       blue = static_cast<int>(val * max_color.blue()  + ((1.0 - val) * min_color.blue()));
00243       return QColor(red, green, blue, 255);
00244     }
00245   }
00246 
00247   void LaserScanPlugin::UpdateColors()
00248   {
00249     std::deque<Scan>::iterator scan_it = scans_.begin();
00250     for (; scan_it != scans_.end(); ++scan_it)
00251     {
00252       std::vector<StampedPoint>::iterator point_it = scan_it->points.begin();
00253       for (; point_it != scan_it->points.end(); point_it++)
00254       {
00255         point_it->color = CalculateColor(*point_it, scan_it->has_intensity);
00256       }
00257     }
00258   }
00259 
00260   void LaserScanPlugin::SelectTopic()
00261   {
00262     ros::master::TopicInfo topic = mapviz::SelectTopicDialog::selectTopic(
00263       "sensor_msgs/LaserScan");
00264 
00265     if (!topic.name.empty())
00266     {
00267       ui_.topic->setText(QString::fromStdString(topic.name));
00268       TopicEdited();
00269     }
00270   }
00271 
00272   void LaserScanPlugin::TopicEdited()
00273   {
00274     std::string topic = ui_.topic->text().trimmed().toStdString();
00275     if (topic != topic_)
00276     {
00277       initialized_ = false;
00278       scans_.clear();
00279       has_message_ = false;
00280       PrintWarning("No messages received.");
00281 
00282       laserscan_sub_.shutdown();
00283 
00284       topic_ = topic;
00285       if (!topic.empty())
00286       {
00287         laserscan_sub_ = node_.subscribe(topic_,
00288                                          100,
00289                                          &LaserScanPlugin::laserScanCallback,
00290                                          this);
00291 
00292         ROS_INFO("Subscribing to %s", topic_.c_str());
00293       }
00294     }
00295   }
00296 
00297   void LaserScanPlugin::MinValueChanged(double value)
00298   {
00299     min_value_ = value;
00300     UpdateColors();
00301   }
00302 
00303   void LaserScanPlugin::MaxValueChanged(double value)
00304   {
00305     max_value_ = value;
00306     UpdateColors();
00307   }
00308 
00309   void LaserScanPlugin::BufferSizeChanged(int value)
00310   {
00311     buffer_size_ = static_cast<size_t>(value);
00312 
00313     if (buffer_size_ > 0)
00314     {
00315       while (scans_.size() > buffer_size_)
00316       {
00317         scans_.pop_front();
00318       }
00319     }
00320   }
00321 
00322   void LaserScanPlugin::PointSizeChanged(int value)
00323   {
00324     point_size_ = static_cast<size_t>(value);
00325   }
00326 
00327   void LaserScanPlugin::laserScanCallback(const sensor_msgs::LaserScanConstPtr& msg)
00328   {
00329     if (!has_message_)
00330     {
00331       initialized_ = true;
00332       has_message_ = true;
00333     }
00334 
00335     // Note that unlike some plugins, this one does not store nor rely on the
00336     // source_frame_ member variable.  This one can potentially store many
00337     // messages with different source frames, so we need to store and transform
00338     // them individually.
00339 
00340     Scan scan;
00341     scan.stamp = msg->header.stamp;
00342     scan.color = QColor::fromRgbF(1.0f, 0.0f, 0.0f, 1.0f);
00343     scan.source_frame_ = msg->header.frame_id;
00344     scan.transformed = true;
00345     scan.has_intensity = !msg->intensities.empty();
00346 
00347     scan.points.clear();
00348 
00349     swri_transform_util::Transform transform;
00350     if (!GetTransform(scan.source_frame_, msg->header.stamp, transform))
00351     {
00352       scan.transformed = false;
00353       PrintError("No transform between " + source_frame_ + " and " + target_frame_);
00354     }
00355     double angle, x, y;
00356     for (size_t i = 0; i < msg->ranges.size(); i++)
00357     {
00358       // Discard the point if it's out of range
00359       if (msg->ranges[i] > msg->range_max || msg->ranges[i] < msg->range_min)
00360       {
00361         continue;
00362       }
00363       StampedPoint point;
00364       angle = msg->angle_min + msg->angle_increment * i;
00365       x = cos(angle) * msg->ranges[i];
00366       y = sin(angle) * msg->ranges[i];
00367       point.point = tf::Point(x, y, 0.0f);
00368       point.range = msg->ranges[i];
00369       if (i < msg->intensities.size())
00370         point.intensity = msg->intensities[i];
00371       if (scan.transformed)
00372       {
00373         point.transformed_point = transform * point.point;
00374       }
00375       point.color = CalculateColor(point, scan.has_intensity);
00376       scan.points.push_back(point);
00377     }
00378     scans_.push_back(scan);
00379 
00380     // If there are more items in the scan buffer than buffer_size_, remove them
00381     if (buffer_size_ > 0)
00382     {
00383       while (scans_.size() > buffer_size_)
00384       {
00385         scans_.pop_front();
00386       }
00387     }
00388   }
00389 
00390   void LaserScanPlugin::PrintError(const std::string& message)
00391   {
00392     if (message == ui_.status->text().toStdString())
00393     {
00394       return;
00395     }
00396 
00397     ROS_ERROR("Error: %s", message.c_str());
00398     QPalette p(ui_.status->palette());
00399     p.setColor(QPalette::Text, Qt::red);
00400     ui_.status->setPalette(p);
00401     ui_.status->setText(message.c_str());
00402   }
00403 
00404   void LaserScanPlugin::PrintInfo(const std::string& message)
00405   {
00406     if (message == ui_.status->text().toStdString())
00407     {
00408       return;
00409     }
00410 
00411     ROS_INFO("%s", message.c_str());
00412     QPalette p(ui_.status->palette());
00413     p.setColor(QPalette::Text, Qt::green);
00414     ui_.status->setPalette(p);
00415     ui_.status->setText(message.c_str());
00416   }
00417 
00418   void LaserScanPlugin::PrintWarning(const std::string& message)
00419   {
00420     if (message == ui_.status->text().toStdString())
00421     {
00422       return;
00423     }
00424 
00425     ROS_WARN("%s", message.c_str());
00426     QPalette p(ui_.status->palette());
00427     p.setColor(QPalette::Text, Qt::darkYellow);
00428     ui_.status->setPalette(p);
00429     ui_.status->setText(message.c_str());
00430   }
00431 
00432   QWidget* LaserScanPlugin::GetConfigWidget(QWidget* parent)
00433   {
00434     config_widget_->setParent(parent);
00435 
00436     return config_widget_;
00437   }
00438 
00439   bool LaserScanPlugin::Initialize(QGLWidget* canvas)
00440   {
00441     canvas_ = canvas;
00442 
00443     DrawIcon();
00444 
00445     return true;
00446   }
00447 
00448   void LaserScanPlugin::Draw(double x, double y, double scale)
00449   {
00450     glPointSize(point_size_);
00451     glBegin(GL_POINTS);
00452 
00453     std::deque<Scan>::const_iterator scan_it = scans_.begin();
00454     while (scan_it != scans_.end())
00455     {
00456       if (scan_it->transformed)
00457       {
00458         std::vector<StampedPoint>::const_iterator point_it = scan_it->points.begin();
00459         for (; point_it != scan_it->points.end(); ++point_it)
00460         {
00461           glColor4d(
00462               point_it->color.redF(),
00463               point_it->color.greenF(),
00464               point_it->color.blueF(),
00465               alpha_);
00466           glVertex2d(
00467               point_it->transformed_point.getX(),
00468               point_it->transformed_point.getY());
00469         }
00470       }
00471       ++scan_it;
00472     }
00473 
00474     glEnd();
00475 
00476     PrintInfo("OK");
00477   }
00478 
00479   void LaserScanPlugin::UseRainbowChanged(int check_state)
00480   {
00481     if (check_state == Qt::Checked)
00482     {
00483       ui_.max_color->setVisible(false);
00484       ui_.min_color->setVisible(false);
00485       ui_.maxColorLabel->setVisible(false);
00486       ui_.minColorLabel->setVisible(false);
00487     }
00488     else
00489     {
00490       ui_.max_color->setVisible(true);
00491       ui_.min_color->setVisible(true);
00492       ui_.maxColorLabel->setVisible(true);
00493       ui_.minColorLabel->setVisible(true);
00494     }
00495     UpdateColors();
00496   }
00497 
00498   void LaserScanPlugin::Transform()
00499   {
00500     std::deque<Scan>::iterator scan_it = scans_.begin();
00501     for (; scan_it != scans_.end(); ++scan_it)
00502     {
00503       Scan& scan = *scan_it;
00504 
00505       swri_transform_util::Transform transform;
00506 
00507       bool was_using_latest_transforms = this->use_latest_transforms_;
00508       this->use_latest_transforms_ = false;
00509       if (GetTransform(scan.source_frame_, scan.stamp, transform))
00510       {
00511         scan.transformed = true;
00512         std::vector<StampedPoint>::iterator point_it = scan.points.begin();
00513         for (; point_it != scan.points.end(); ++point_it)
00514         {
00515           point_it->transformed_point = transform * point_it->point;
00516         }
00517       }
00518       else
00519       {
00520         scan.transformed = false;
00521       }
00522       this->use_latest_transforms_ = was_using_latest_transforms;
00523     }
00524     // Z color is based on transformed color, so it is dependent on the
00525     // transform
00526     if (ui_.color_transformer->currentIndex() == COLOR_Z)
00527     {
00528       UpdateColors();
00529     }
00530   }
00531 
00532   void LaserScanPlugin::LoadConfig(const YAML::Node& node,
00533       const std::string& path)
00534   {
00535     if (node["topic"])
00536     {
00537       std::string topic;
00538       node["topic"] >> topic;
00539       ui_.topic->setText(boost::trim_copy(topic).c_str());
00540       TopicEdited();
00541     }
00542 
00543     if (node["size"])
00544     {
00545       node["size"] >> point_size_;
00546       ui_.pointSize->setValue(static_cast<int>(point_size_));
00547     }
00548 
00549     if (node["buffer_size"])
00550     {
00551       node["buffer_size"] >> buffer_size_;
00552       ui_.bufferSize->setValue(static_cast<int>(buffer_size_));
00553     }
00554 
00555     if (node["color_transformer"])
00556     {
00557       std::string color_transformer;
00558       node["color_transformer"] >> color_transformer;
00559       if (color_transformer == "Intensity")
00560         ui_.color_transformer->setCurrentIndex(COLOR_INTENSITY);
00561       else if (color_transformer == "Range")
00562         ui_.color_transformer->setCurrentIndex(COLOR_RANGE);
00563       else if (color_transformer == "X Axis")
00564         ui_.color_transformer->setCurrentIndex(COLOR_X);
00565       else if (color_transformer == "Y Axis")
00566         ui_.color_transformer->setCurrentIndex(COLOR_Y);
00567       else if (color_transformer == "Z Axis")
00568         ui_.color_transformer->setCurrentIndex(COLOR_Z);
00569       else
00570         ui_.color_transformer->setCurrentIndex(COLOR_FLAT);
00571     }
00572 
00573     if (node["min_color"])
00574     {
00575       std::string min_color_str;
00576       node["min_color"] >> min_color_str;
00577       ui_.min_color->setColor(QColor(min_color_str.c_str()));
00578     }
00579 
00580     if (node["max_color"])
00581     {
00582       std::string max_color_str;
00583       node["max_color"] >> max_color_str;
00584       ui_.max_color->setColor(QColor(max_color_str.c_str()));
00585     }
00586 
00587     if (node["value_min"])
00588     {
00589       node["value_min"] >> min_value_;
00590       ui_.minValue->setValue(min_value_);
00591     }
00592 
00593     if (node["max_value"])
00594     {
00595       node["value_max"] >> max_value_;
00596       ui_.maxValue->setValue(max_value_);
00597     }
00598 
00599     if (node["alpha"])
00600     {
00601       node["alpha"] >> alpha_;
00602       ui_.alpha->setValue(alpha_);
00603       AlphaEdited();
00604     }
00605 
00606     if (node["use_rainbow"])
00607     {
00608       bool use_rainbow;
00609       node["use_rainbow"] >> use_rainbow;
00610       ui_.use_rainbow->setChecked(use_rainbow);
00611     }
00612 
00613     // UseRainbowChanged must be called *before* ColorTransformerChanged
00614     UseRainbowChanged(ui_.use_rainbow->checkState());
00615     // ColorTransformerChanged will also update colors of all points
00616     ColorTransformerChanged(ui_.color_transformer->currentIndex());
00617   }
00618 
00619   void LaserScanPlugin::ColorTransformerChanged(int index)
00620   {
00621     ROS_DEBUG("Color transformer changed to %d", index);
00622     switch (index)
00623     {
00624       case COLOR_FLAT:
00625         ui_.min_color->setVisible(true);
00626         ui_.max_color->setVisible(false);
00627         ui_.maxColorLabel->setVisible(false);
00628         ui_.minColorLabel->setVisible(false);
00629         ui_.minValueLabel->setVisible(false);
00630         ui_.maxValueLabel->setVisible(false);
00631         ui_.minValue->setVisible(false);
00632         ui_.maxValue->setVisible(false);
00633         ui_.use_rainbow->setVisible(false);
00634         break;
00635       case COLOR_INTENSITY:  // Intensity
00636       case COLOR_RANGE:  // Range
00637       case COLOR_X:  // X Axis
00638       case COLOR_Y:  // Y Axis
00639       case COLOR_Z:  // Z axis
00640       default:
00641         ui_.min_color->setVisible(!ui_.use_rainbow->isChecked());
00642         ui_.max_color->setVisible(!ui_.use_rainbow->isChecked());
00643         ui_.maxColorLabel->setVisible(!ui_.use_rainbow->isChecked());
00644         ui_.minColorLabel->setVisible(!ui_.use_rainbow->isChecked());
00645         ui_.minValueLabel->setVisible(true);
00646         ui_.maxValueLabel->setVisible(true);
00647         ui_.minValue->setVisible(true);
00648         ui_.maxValue->setVisible(true);
00649         ui_.use_rainbow->setVisible(true);
00650         break;
00651     }
00652     UpdateColors();
00653   }
00654 
00658   void LaserScanPlugin::AlphaEdited()
00659   {
00660     alpha_ = std::max(0.0f, std::min(ui_.alpha->text().toFloat(), 1.0f));
00661     ui_.alpha->setValue(alpha_);
00662   }
00663 
00664   void LaserScanPlugin::SaveConfig(YAML::Emitter& emitter,
00665       const std::string& path)
00666   {
00667     emitter << YAML::Key << "topic" <<
00668                YAML::Value << boost::trim_copy(ui_.topic->text().toStdString());
00669     emitter << YAML::Key << "size" <<
00670                YAML::Value << ui_.pointSize->value();
00671     emitter << YAML::Key << "buffer_size" <<
00672                YAML::Value << ui_.bufferSize->value();
00673     emitter << YAML::Key << "alpha" <<
00674                YAML::Value << alpha_;
00675     emitter << YAML::Key << "color_transformer" <<
00676                YAML::Value << ui_.color_transformer->currentText().toStdString();
00677     emitter << YAML::Key << "min_color" <<
00678                YAML::Value << ui_.min_color->color().name().toStdString();
00679     emitter << YAML::Key << "max_color" <<
00680                YAML::Value << ui_.max_color->color().name().toStdString();
00681     emitter << YAML::Key << "value_min" <<
00682                YAML::Value << ui_.minValue->text().toDouble();
00683     emitter << YAML::Key << "value_max" <<
00684                YAML::Value << ui_.maxValue->text().toDouble();
00685     emitter << YAML::Key << "use_rainbow" <<
00686                YAML::Value << ui_.use_rainbow->isChecked();
00687   }
00688 }
00689 


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