disparity_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/disparity_plugin.h>
00031 
00032 // C++ standard libraries
00033 #include <cstdio>
00034 #include <algorithm>
00035 #include <vector>
00036 
00037 // QT libraries
00038 #include <QDialog>
00039 #include <QGLWidget>
00040 
00041 // ROS libraries
00042 #include <ros/master.h>
00043 #include <sensor_msgs/image_encodings.h>
00044 #include <opencv2/imgproc/imgproc.hpp>
00045 
00046 #include <cv_bridge/cv_bridge.h>
00047 
00048 #include <mapviz/select_topic_dialog.h>
00049 
00050 // Declare plugin
00051 #include <pluginlib/class_list_macros.h>
00052 PLUGINLIB_EXPORT_CLASS(mapviz_plugins::DisparityPlugin, mapviz::MapvizPlugin)
00053 
00054 namespace mapviz_plugins
00055 {
00056   DisparityPlugin::DisparityPlugin() :
00057     config_widget_(new QWidget()),
00058     anchor_(TOP_LEFT),
00059     units_(PIXELS),
00060     offset_x_(0),
00061     offset_y_(0),
00062     width_(320),
00063     height_(240),
00064     has_image_(false),
00065     last_width_(0),
00066     last_height_(0)
00067   {
00068     ui_.setupUi(config_widget_);
00069 
00070     // Set background white
00071     QPalette p(config_widget_->palette());
00072     p.setColor(QPalette::Background, Qt::white);
00073     config_widget_->setPalette(p);
00074 
00075     // Set status text red
00076     QPalette p3(ui_.status->palette());
00077     p3.setColor(QPalette::Text, Qt::red);
00078     ui_.status->setPalette(p3);
00079 
00080     QObject::connect(ui_.selecttopic, SIGNAL(clicked()), this, SLOT(SelectTopic()));
00081     QObject::connect(ui_.topic, SIGNAL(editingFinished()), this, SLOT(TopicEdited()));
00082     QObject::connect(ui_.anchor, SIGNAL(activated(QString)), this, SLOT(SetAnchor(QString)));
00083     QObject::connect(ui_.units, SIGNAL(activated(QString)), this, SLOT(SetUnits(QString)));
00084     QObject::connect(ui_.offsetx, SIGNAL(valueChanged(int)), this, SLOT(SetOffsetX(int)));
00085     QObject::connect(ui_.offsety, SIGNAL(valueChanged(int)), this, SLOT(SetOffsetY(int)));
00086     QObject::connect(ui_.width, SIGNAL(valueChanged(int)), this, SLOT(SetWidth(int)));
00087     QObject::connect(ui_.height, SIGNAL(valueChanged(int)), this, SLOT(SetHeight(int)));
00088     QObject::connect(this,SIGNAL(VisibleChanged(bool)),this,SLOT(SetSubscription(bool)));
00089   }
00090 
00091   DisparityPlugin::~DisparityPlugin()
00092   {
00093   }
00094 
00095   void DisparityPlugin::SetOffsetX(int offset)
00096   {
00097     offset_x_ = offset;
00098   }
00099 
00100   void DisparityPlugin::SetOffsetY(int offset)
00101   {
00102     offset_y_ = offset;
00103   }
00104 
00105   void DisparityPlugin::SetWidth(int width)
00106   {
00107     width_ = width;
00108   }
00109 
00110   void DisparityPlugin::SetHeight(int height)
00111   {
00112     height_ = height;
00113   }
00114 
00115   void DisparityPlugin::SetAnchor(QString anchor)
00116   {
00117     if (anchor == "top left")
00118     {
00119       anchor_ = TOP_LEFT;
00120     }
00121     else if (anchor == "top center")
00122     {
00123       anchor_ = TOP_CENTER;
00124     }
00125     else if (anchor == "top right")
00126     {
00127       anchor_ = TOP_RIGHT;
00128     }
00129     else if (anchor == "center left")
00130     {
00131       anchor_ = CENTER_LEFT;
00132     }
00133     else if (anchor == "center")
00134     {
00135       anchor_ = CENTER;
00136     }
00137     else if (anchor == "center right")
00138     {
00139       anchor_ = CENTER_RIGHT;
00140     }
00141     else if (anchor == "bottom left")
00142     {
00143       anchor_ = BOTTOM_LEFT;
00144     }
00145     else if (anchor == "bottom center")
00146     {
00147       anchor_ = BOTTOM_CENTER;
00148     }
00149     else if (anchor == "bottom right")
00150     {
00151       anchor_ = BOTTOM_RIGHT;
00152     }
00153   }
00154 
00155   void DisparityPlugin::SetUnits(QString units)
00156   {
00157     if (units == "pixels")
00158     {
00159       units_ = PIXELS;
00160     }
00161     else if (units == "percent")
00162     {
00163       units_ = PERCENT;
00164     }
00165   }
00166   void DisparityPlugin::SetSubscription(bool visible)
00167   {
00168     if(topic_.empty())
00169     {
00170       return;
00171     }
00172     else if(!visible)
00173     {
00174       disparity_sub_.shutdown();
00175       ROS_INFO("Dropped subscription to %s", topic_.c_str());
00176     }
00177     else
00178     {
00179       disparity_sub_ = node_.subscribe(topic_, 1, &DisparityPlugin::disparityCallback, this);
00180 
00181       ROS_INFO("Subscribing to %s", topic_.c_str());
00182     }
00183   }
00184   void DisparityPlugin::SelectTopic()
00185   {
00186     ros::master::TopicInfo topic = mapviz::SelectTopicDialog::selectTopic(
00187       "stereo_msgs/DisparityImage");
00188 
00189     if(topic.name.empty())
00190     {
00191       topic.name.clear();
00192       TopicEdited();
00193     }
00194     if (!topic.name.empty())
00195     {
00196       ui_.topic->setText(QString::fromStdString(topic.name));
00197       TopicEdited();
00198     }
00199 
00200   }
00201 
00202   void DisparityPlugin::TopicEdited()
00203   {
00204     std::string topic = ui_.topic->text().trimmed().toStdString();
00205     if(!this->Visible())
00206     {
00207       PrintWarning("Topic is Hidden");
00208       initialized_ = false;
00209       has_message_ = false;
00210       if (!topic.empty())
00211       {
00212         topic_ = topic;
00213       }
00214       disparity_sub_.shutdown();
00215       return;
00216     }
00217     if (topic != topic_)
00218     {
00219       initialized_ = false;
00220       has_message_ = false;
00221       topic_ = topic;
00222       PrintWarning("No messages received.");
00223 
00224       disparity_sub_.shutdown();
00225 
00226       if (!topic.empty())
00227       {
00228         disparity_sub_ = node_.subscribe(topic_, 1, &DisparityPlugin::disparityCallback, this);
00229 
00230         ROS_INFO("Subscribing to %s", topic_.c_str());
00231       }
00232     }
00233   }
00234 
00235   void DisparityPlugin::disparityCallback(const stereo_msgs::DisparityImageConstPtr& disparity)
00236   {
00237     if (!has_message_)
00238     {
00239       initialized_ = true;
00240       has_message_ = true;
00241     }
00242 
00243     if (disparity->min_disparity == 0.0 && disparity->max_disparity == 0.0)
00244     {
00245       PrintError("Min and max disparity not set.");
00246       has_image_ = false;
00247       return;
00248     }
00249 
00250     if (disparity->image.encoding != sensor_msgs::image_encodings::TYPE_32FC1)
00251     {
00252       PrintError("Invalid encoding.");
00253       has_image_ = false;
00254       return;
00255     }
00256 
00257     disparity_ = *disparity;
00258 
00259     // Colormap and display the disparity image
00260     float min_disparity = disparity->min_disparity;
00261     float max_disparity = disparity->max_disparity;
00262     float multiplier = 255.0f / (max_disparity - min_disparity);
00263 
00264     cv_bridge::CvImageConstPtr cv_disparity = 
00265       cv_bridge::toCvShare(disparity->image, disparity);
00266 
00267     disparity_color_.create(disparity->image.height, disparity->image.width);
00268 
00269     for (int row = 0; row < disparity_color_.rows; row++)
00270     {
00271       const float* d = cv_disparity->image.ptr<float>(row);
00272       for (int col = 0; col < disparity_color_.cols; col++)
00273       {
00274         int index = static_cast<int>((d[col] - min_disparity) * multiplier + 0.5);
00275         index = std::min(255, std::max(0, index));
00276         // Fill as BGR
00277         disparity_color_(row, col)[2] = COLOR_MAP[3*index + 0];
00278         disparity_color_(row, col)[1] = COLOR_MAP[3*index + 1];
00279         disparity_color_(row, col)[0] = COLOR_MAP[3*index + 2];
00280       }
00281     }
00282 
00283     last_width_ = 0;
00284     last_height_ = 0;
00285 
00286     has_image_ = true;
00287   }
00288 
00289   void DisparityPlugin::PrintError(const std::string& message)
00290   {
00291     PrintErrorHelper(ui_.status, message);
00292   }
00293 
00294   void DisparityPlugin::PrintInfo(const std::string& message)
00295   {
00296     PrintInfoHelper(ui_.status, message);
00297   }
00298 
00299   void DisparityPlugin::PrintWarning(const std::string& message)
00300   {
00301     PrintWarningHelper(ui_.status, message);
00302   }
00303 
00304   QWidget* DisparityPlugin::GetConfigWidget(QWidget* parent)
00305   {
00306     config_widget_->setParent(parent);
00307 
00308     return config_widget_;
00309   }
00310 
00311   bool DisparityPlugin::Initialize(QGLWidget* canvas)
00312   {
00313     canvas_ = canvas;
00314 
00315     return true;
00316   }
00317 
00318   void DisparityPlugin::ScaleImage(double width, double height)
00319   {
00320     if (!has_image_)
00321     {
00322       return;
00323     }
00324 
00325     cv::resize(disparity_color_, scaled_image_, cvSize2D32f(width, height), 0, 0, CV_INTER_AREA);
00326   }
00327 
00328   void DisparityPlugin::DrawIplImage(cv::Mat *image)
00329   {
00330     // TODO(malban): glTexture2D may be more efficient than glDrawPixels
00331 
00332     if (!has_image_)
00333       return;
00334 
00335     if (image == NULL)
00336       return;
00337 
00338     if (image->cols == 0 || image->rows == 0)
00339       return;
00340 
00341     GLenum format;
00342     switch (image->channels())
00343     {
00344       case 1:
00345         format = GL_LUMINANCE;
00346         break;
00347       case 2:
00348         format = GL_LUMINANCE_ALPHA;
00349         break;
00350       case 3:
00351         format = GL_BGR;
00352         break;
00353       default:
00354         return;
00355     }
00356 
00357     glPixelZoom(1.0, -1.0f);
00358     glDrawPixels(image->cols, image->rows, format, GL_UNSIGNED_BYTE, image->ptr());
00359 
00360     PrintInfo("OK");
00361   }
00362 
00363   void DisparityPlugin::Draw(double x, double y, double scale)
00364   {
00365     // Calculate the correct offsets and dimensions
00366     double x_offset = offset_x_;
00367     double y_offset = offset_y_;
00368     double width = width_;
00369     double height = height_;
00370     if (units_ == PERCENT)
00371     {
00372       x_offset = offset_x_ * canvas_->width() / 100.0;
00373       y_offset = offset_y_ * canvas_->height() / 100.0;
00374       width = width_ * canvas_->width() / 100.0;
00375       height = height_ * canvas_->height() / 100.0;
00376     }
00377 
00378     // Scale the source image if necessary
00379     if (width != last_width_ || height != last_height_)
00380     {
00381       ScaleImage(width, height);
00382     }
00383 
00384     // Calculate the correct render position
00385     double x_pos = 0;
00386     double y_pos = 0;
00387     if (anchor_ == TOP_LEFT)
00388     {
00389       x_pos = x_offset;
00390       y_pos = y_offset;
00391     }
00392     else if (anchor_ == TOP_CENTER)
00393     {
00394       x_pos = (canvas_->width() - width) / 2.0 + x_offset;
00395       y_pos = y_offset;
00396     }
00397     else if (anchor_ == TOP_RIGHT)
00398     {
00399       x_pos = canvas_->width() - width - x_offset;
00400       y_pos = y_offset;
00401     }
00402     else if (anchor_ == CENTER_LEFT)
00403     {
00404       x_pos = x_offset;
00405       y_pos = (canvas_->height() - height) / 2.0 + y_offset;
00406     }
00407     else if (anchor_ == CENTER)
00408     {
00409       x_pos = (canvas_->width() - width) / 2.0 + x_offset;
00410       y_pos = (canvas_->height() - height) / 2.0 + y_offset;
00411     }
00412     else if (anchor_ == CENTER_RIGHT)
00413     {
00414       x_pos = canvas_->width() - width - x_offset;
00415       y_pos = (canvas_->height() - height) / 2.0 + y_offset;
00416     }
00417     else if (anchor_ == BOTTOM_LEFT)
00418     {
00419       x_pos = x_offset;
00420       y_pos = canvas_->height() - height - y_offset;
00421     }
00422     else if (anchor_ == BOTTOM_CENTER)
00423     {
00424       x_pos = (canvas_->width() - width) / 2.0 + x_offset;
00425       y_pos = canvas_->height() - height - y_offset;
00426     }
00427     else if (anchor_ == BOTTOM_RIGHT)
00428     {
00429       x_pos = canvas_->width() - width - x_offset;
00430       y_pos = canvas_->height() - height - y_offset;
00431     }
00432 
00433     glMatrixMode(GL_PROJECTION);
00434     glPushMatrix();
00435     glLoadIdentity();
00436     glOrtho(0, canvas_->width(), canvas_->height(), 0, -0.5f, 0.5f);
00437 
00438     glRasterPos2d(x_pos, y_pos);
00439 
00440     DrawIplImage(&scaled_image_);
00441 
00442     glPopMatrix();
00443 
00444     last_width_ = width;
00445     last_height_ = height;
00446   }
00447 
00448   void DisparityPlugin::LoadConfig(const YAML::Node& node, const std::string& path)
00449   {
00450     if (node["topic"])
00451     {
00452       std::string topic;
00453       node["topic"] >> topic;
00454       ui_.topic->setText(topic.c_str());
00455       TopicEdited();
00456     }
00457 
00458     if (node["anchor"])
00459     {             
00460       std::string anchor;
00461       node["anchor"] >> anchor;
00462       ui_.anchor->setCurrentIndex(ui_.anchor->findText(anchor.c_str()));
00463       SetAnchor(anchor.c_str());
00464     }
00465 
00466     if (node["units"])
00467     {
00468       std::string units;
00469       node["units"] >> units;
00470       ui_.units->setCurrentIndex(ui_.units->findText(units.c_str()));
00471       SetUnits(units.c_str());
00472     }
00473 
00474     if (node["offset_x"])
00475     {
00476       node["offset_x"] >> offset_x_;
00477       ui_.offsetx->setValue(static_cast<int>(offset_x_));
00478     }
00479 
00480     if (node["offset_y"])
00481     {
00482       node["offset_y"] >> offset_y_;
00483       ui_.offsety->setValue(static_cast<int>(offset_y_));
00484     }
00485 
00486     if (node["width"])
00487     {
00488       node["width"] >> width_;
00489       ui_.width->setValue(static_cast<int>(width_));
00490     }
00491 
00492     if (node["height"])
00493     {             
00494       node["height"] >> height_;
00495       ui_.height->setValue(static_cast<int>(height_));
00496     }
00497   }
00498 
00499   void DisparityPlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path)
00500   {
00501     emitter << YAML::Key << "topic" << YAML::Value << ui_.topic->text().toStdString();
00502     emitter << YAML::Key << "anchor" << YAML::Value << AnchorToString(anchor_);
00503     emitter << YAML::Key << "units" << YAML::Value << UnitsToString(units_);
00504     emitter << YAML::Key << "offset_x" << YAML::Value << offset_x_;
00505     emitter << YAML::Key << "offset_y" << YAML::Value << offset_y_;
00506     emitter << YAML::Key << "width" << YAML::Value << width_;
00507     emitter << YAML::Key << "height" << YAML::Value << height_;
00508   }
00509 
00510   std::string DisparityPlugin::AnchorToString(Anchor anchor)
00511   {
00512     std::string anchor_string = "top left";
00513 
00514     if (anchor == TOP_LEFT)
00515     {
00516       anchor_string = "top left";
00517     }
00518     else if (anchor == TOP_CENTER)
00519     {
00520       anchor_string = "top center";
00521     }
00522     else if (anchor == TOP_RIGHT)
00523     {
00524       anchor_string = "top right";
00525     }
00526     else if (anchor == CENTER_LEFT)
00527     {
00528       anchor_string = "center left";
00529     }
00530     else if (anchor == CENTER)
00531     {
00532       anchor_string = "center";
00533     }
00534     else if (anchor == CENTER_RIGHT)
00535     {
00536       anchor_string = "center right";
00537     }
00538     else if (anchor == BOTTOM_LEFT)
00539     {
00540       anchor_string = "bottom left";
00541     }
00542     else if (anchor == BOTTOM_CENTER)
00543     {
00544       anchor_string = "bottom center";
00545     }
00546     else if (anchor == BOTTOM_RIGHT)
00547     {
00548       anchor_string = "bottom right";
00549     }
00550 
00551     return anchor_string;
00552   }
00553 
00554   std::string DisparityPlugin::UnitsToString(Units units)
00555   {
00556     std::string units_string = "pixels";
00557 
00558     if (units == PIXELS)
00559     {
00560       units_string = "pixels";
00561     }
00562     else if (units == PERCENT)
00563     {
00564       units_string = "percent";
00565     }
00566 
00567     return units_string;
00568   }
00569 
00570   const unsigned char DisparityPlugin::COLOR_MAP[768] =
00571     { 150, 150, 150,
00572       107, 0, 12,
00573       106, 0, 18,
00574       105, 0, 24,
00575       103, 0, 30,
00576       102, 0, 36,
00577       101, 0, 42,
00578       99, 0, 48,
00579       98, 0, 54,
00580       97, 0, 60,
00581       96, 0, 66,
00582       94, 0, 72,
00583       93, 0, 78,
00584       92, 0, 84,
00585       91, 0, 90,
00586       89, 0, 96,
00587       88, 0, 102,
00588       87, 0, 108,
00589       85, 0, 114,
00590       84, 0, 120,
00591       83, 0, 126,
00592       82, 0, 131,
00593       80, 0, 137,
00594       79, 0, 143,
00595       78, 0, 149,
00596       77, 0, 155,
00597       75, 0, 161,
00598       74, 0, 167,
00599       73, 0, 173,
00600       71, 0, 179,
00601       70, 0, 185,
00602       69, 0, 191,
00603       68, 0, 197,
00604       66, 0, 203,
00605       65, 0, 209,
00606       64, 0, 215,
00607       62, 0, 221,
00608       61, 0, 227,
00609       60, 0, 233,
00610       59, 0, 239,
00611       57, 0, 245,
00612       56, 0, 251,
00613       55, 0, 255,
00614       54, 0, 255,
00615       52, 0, 255,
00616       51, 0, 255,
00617       50, 0, 255,
00618       48, 0, 255,
00619       47, 0, 255,
00620       46, 0, 255,
00621       45, 0, 255,
00622       43, 0, 255,
00623       42, 0, 255,
00624       41, 0, 255,
00625       40, 0, 255,
00626       38, 0, 255,
00627       37, 0, 255,
00628       36, 0, 255,
00629       34, 0, 255,
00630       33, 0, 255,
00631       32, 0, 255,
00632       31, 0, 255,
00633       29, 0, 255,
00634       28, 0, 255,
00635       27, 0, 255,
00636       26, 0, 255,
00637       24, 0, 255,
00638       23, 0, 255,
00639       22, 0, 255,
00640       20, 0, 255,
00641       19, 0, 255,
00642       18, 0, 255,
00643       17, 0, 255,
00644       15, 0, 255,
00645       14, 0, 255,
00646       13, 0, 255,
00647       11, 0, 255,
00648       10, 0, 255,
00649       9, 0, 255,
00650       8, 0, 255,
00651       6, 0, 255,
00652       5, 0, 255,
00653       4, 0, 255,
00654       3, 0, 255,
00655       1, 0, 255,
00656       0, 4, 255,
00657       0, 10, 255,
00658       0, 16, 255,
00659       0, 22, 255,
00660       0, 28, 255,
00661       0, 34, 255,
00662       0, 40, 255,
00663       0, 46, 255,
00664       0, 52, 255,
00665       0, 58, 255,
00666       0, 64, 255,
00667       0, 70, 255,
00668       0, 76, 255,
00669       0, 82, 255,
00670       0, 88, 255,
00671       0, 94, 255,
00672       0, 100, 255,
00673       0, 106, 255,
00674       0, 112, 255,
00675       0, 118, 255,
00676       0, 124, 255,
00677       0, 129, 255,
00678       0, 135, 255,
00679       0, 141, 255,
00680       0, 147, 255,
00681       0, 153, 255,
00682       0, 159, 255,
00683       0, 165, 255,
00684       0, 171, 255,
00685       0, 177, 255,
00686       0, 183, 255,
00687       0, 189, 255,
00688       0, 195, 255,
00689       0, 201, 255,
00690       0, 207, 255,
00691       0, 213, 255,
00692       0, 219, 255,
00693       0, 225, 255,
00694       0, 231, 255,
00695       0, 237, 255,
00696       0, 243, 255,
00697       0, 249, 255,
00698       0, 255, 255,
00699       0, 255, 249,
00700       0, 255, 243,
00701       0, 255, 237,
00702       0, 255, 231,
00703       0, 255, 225,
00704       0, 255, 219,
00705       0, 255, 213,
00706       0, 255, 207,
00707       0, 255, 201,
00708       0, 255, 195,
00709       0, 255, 189,
00710       0, 255, 183,
00711       0, 255, 177,
00712       0, 255, 171,
00713       0, 255, 165,
00714       0, 255, 159,
00715       0, 255, 153,
00716       0, 255, 147,
00717       0, 255, 141,
00718       0, 255, 135,
00719       0, 255, 129,
00720       0, 255, 124,
00721       0, 255, 118,
00722       0, 255, 112,
00723       0, 255, 106,
00724       0, 255, 100,
00725       0, 255, 94,
00726       0, 255, 88,
00727       0, 255, 82,
00728       0, 255, 76,
00729       0, 255, 70,
00730       0, 255, 64,
00731       0, 255, 58,
00732       0, 255, 52,
00733       0, 255, 46,
00734       0, 255, 40,
00735       0, 255, 34,
00736       0, 255, 28,
00737       0, 255, 22,
00738       0, 255, 16,
00739       0, 255, 10,
00740       0, 255, 4,
00741       2, 255, 0,
00742       8, 255, 0,
00743       14, 255, 0,
00744       20, 255, 0,
00745       26, 255, 0,
00746       32, 255, 0,
00747       38, 255, 0,
00748       44, 255, 0,
00749       50, 255, 0,
00750       56, 255, 0,
00751       62, 255, 0,
00752       68, 255, 0,
00753       74, 255, 0,
00754       80, 255, 0,
00755       86, 255, 0,
00756       92, 255, 0,
00757       98, 255, 0,
00758       104, 255, 0,
00759       110, 255, 0,
00760       116, 255, 0,
00761       122, 255, 0,
00762       128, 255, 0,
00763       133, 255, 0,
00764       139, 255, 0,
00765       145, 255, 0,
00766       151, 255, 0,
00767       157, 255, 0,
00768       163, 255, 0,
00769       169, 255, 0,
00770       175, 255, 0,
00771       181, 255, 0,
00772       187, 255, 0,
00773       193, 255, 0,
00774       199, 255, 0,
00775       205, 255, 0,
00776       211, 255, 0,
00777       217, 255, 0,
00778       223, 255, 0,
00779       229, 255, 0,
00780       235, 255, 0,
00781       241, 255, 0,
00782       247, 255, 0,
00783       253, 255, 0,
00784       255, 251, 0,
00785       255, 245, 0,
00786       255, 239, 0,
00787       255, 233, 0,
00788       255, 227, 0,
00789       255, 221, 0,
00790       255, 215, 0,
00791       255, 209, 0,
00792       255, 203, 0,
00793       255, 197, 0,
00794       255, 191, 0,
00795       255, 185, 0,
00796       255, 179, 0,
00797       255, 173, 0,
00798       255, 167, 0,
00799       255, 161, 0,
00800       255, 155, 0,
00801       255, 149, 0,
00802       255, 143, 0,
00803       255, 137, 0,
00804       255, 131, 0,
00805       255, 126, 0,
00806       255, 120, 0,
00807       255, 114, 0,
00808       255, 108, 0,
00809       255, 102, 0,
00810       255, 96, 0,
00811       255, 90, 0,
00812       255, 84, 0,
00813       255, 78, 0,
00814       255, 72, 0,
00815       255, 66, 0,
00816       255, 60, 0,
00817       255, 54, 0,
00818       255, 48, 0,
00819       255, 42, 0,
00820       255, 36, 0,
00821       255, 30, 0,
00822       255, 24, 0,
00823       255, 18, 0,
00824       255, 12, 0,
00825       255,  6, 0,
00826       255,  0, 0,
00827     };
00828 }
00829 


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