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