39 #include <boost/algorithm/string.hpp>
42 #include <QColorDialog>
47 #include "ui_topic_select.h"
63 config_widget_(new QWidget()),
77 p.setColor(QPalette::Background, Qt::white);
81 QPalette p3(
ui_.status->palette());
82 p3.setColor(QPalette::Text, Qt::red);
83 ui_.status->setPalette(p3);
86 ui_.min_color->setColor(Qt::white);
87 ui_.max_color->setColor(Qt::black);
90 ui_.color_transformer->addItem(QString(
"Flat Color"), QVariant(0));
91 ui_.color_transformer->addItem(QString(
"Intensity"), QVariant(1));
92 ui_.color_transformer->addItem(QString(
"Range"), QVariant(2));
93 ui_.color_transformer->addItem(QString(
"X Axis"), QVariant(3));
94 ui_.color_transformer->addItem(QString(
"Y Axis"), QVariant(4));
95 ui_.color_transformer->addItem(QString(
"Z Axis"), QVariant(5));
97 QObject::connect(
ui_.selecttopic,
101 QObject::connect(
ui_.topic,
102 SIGNAL(editingFinished()),
105 QObject::connect(
ui_.alpha,
106 SIGNAL(valueChanged(
double)),
109 QObject::connect(
ui_.color_transformer,
110 SIGNAL(currentIndexChanged(
int)),
113 QObject::connect(
ui_.max_color,
114 SIGNAL(colorEdited(
const QColor &)),
117 QObject::connect(
ui_.min_color,
118 SIGNAL(colorEdited(
const QColor &)),
121 QObject::connect(
ui_.minValue,
122 SIGNAL(valueChanged(
double)),
125 QObject::connect(
ui_.maxValue,
126 SIGNAL(valueChanged(
double)),
129 QObject::connect(
ui_.bufferSize,
130 SIGNAL(valueChanged(
int)),
133 QObject::connect(
ui_.pointSize,
134 SIGNAL(valueChanged(
int)),
137 QObject::connect(
ui_.use_rainbow,
138 SIGNAL(stateChanged(
int)),
142 QObject::connect(
ui_.max_color,
143 SIGNAL(colorEdited(
const QColor &)),
146 QObject::connect(
ui_.min_color,
147 SIGNAL(colorEdited(
const QColor &)),
150 QObject::connect(
this,
155 PrintInfo(
"Constructed LaserScanPlugin");
172 QPixmap icon(16, 16);
173 icon.fill(Qt::transparent);
175 QPainter painter(&icon);
176 painter.setRenderHint(QPainter::Antialiasing,
true);
180 pen.setCapStyle(Qt::RoundCap);
182 pen.setColor(
ui_.min_color->color());
184 painter.drawPoint(2, 13);
186 pen.setColor(
ui_.min_color->color());
188 painter.drawPoint(4, 6);
190 pen.setColor(
ui_.max_color->color());
192 painter.drawPoint(12, 9);
194 pen.setColor(
ui_.max_color->color());
196 painter.drawPoint(13, 2);
206 scan.transformed =
false;
214 int color_transformer =
ui_.color_transformer->currentIndex();
223 else if (color_transformer ==
COLOR_X)
225 val = point.
point.x();
227 else if (color_transformer ==
COLOR_Y)
229 val = point.
point.y();
231 else if (color_transformer ==
COLOR_Z)
237 return ui_.min_color->color();
241 val = std::max(0.0, std::min(val, 1.0));
242 if (
ui_.use_rainbow->isChecked())
245 int hue =
static_cast<int>(val * 255);
246 return QColor::fromHsl(hue, 255, 127, 255);
250 const QColor min_color =
ui_.min_color->color();
251 const QColor max_color =
ui_.max_color->color();
253 int red, green, blue;
254 red =
static_cast<int>(val * max_color.red() + ((1.0 - val) * min_color.red()));
255 green =
static_cast<int>(val * max_color.green() + ((1.0 - val) * min_color.green()));
256 blue =
static_cast<int>(val * max_color.blue() + ((1.0 - val) * min_color.blue()));
257 return QColor(red, green, blue, 255);
263 std::deque<Scan>::iterator scan_it =
scans_.begin();
264 for (; scan_it !=
scans_.end(); ++scan_it)
266 std::vector<StampedPoint>::iterator point_it = scan_it->points.begin();
267 for (; point_it != scan_it->points.end(); point_it++)
269 point_it->color =
CalculateColor(*point_it, scan_it->has_intensity);
277 "sensor_msgs/LaserScan");
279 if (!topic.
name.empty())
281 ui_.topic->setText(QString::fromStdString(topic.
name));
288 std::string topic =
ui_.topic->text().trimmed().toStdString();
354 for (
size_t i = 0; i <
msg->ranges.size(); i++)
356 double angle =
msg->angle_min +
msg->angle_increment * i;
384 scan.
color = QColor::fromRgbF(1.0
f, 0.0
f, 0.0
f, 1.0
f);
387 scan.
points.reserve(
msg->ranges.size() );
395 for (
size_t i = 0; i <
msg->ranges.size(); i++)
398 if (
msg->ranges[i] >
msg->range_max ||
msg->ranges[i] <
msg->range_min)
407 if (i < msg->intensities.size())
415 scan.
points.push_back(point);
465 std::deque<Scan>::const_iterator scan_it =
scans_.begin();
466 while (scan_it !=
scans_.end())
468 if (scan_it->transformed)
470 std::vector<StampedPoint>::const_iterator point_it = scan_it->points.begin();
471 for (; point_it != scan_it->points.end(); ++point_it)
474 point_it->color.redF(),
475 point_it->color.greenF(),
476 point_it->color.blueF(),
479 point_it->transformed_point.getX(),
480 point_it->transformed_point.getY());
493 if (check_state == Qt::Checked)
495 ui_.max_color->setVisible(
false);
496 ui_.min_color->setVisible(
false);
497 ui_.maxColorLabel->setVisible(
false);
498 ui_.minColorLabel->setVisible(
false);
502 ui_.max_color->setVisible(
true);
503 ui_.min_color->setVisible(
true);
504 ui_.maxColorLabel->setVisible(
true);
505 ui_.minColorLabel->setVisible(
true);
512 std::deque<Scan>::iterator scan_it =
scans_.begin();
513 for (; scan_it !=
scans_.end(); ++scan_it)
515 Scan& scan = *scan_it;
524 std::vector<StampedPoint>::iterator point_it = scan.
points.begin();
525 for (; point_it != scan.
points.end(); ++point_it)
527 point_it->transformed_point =
transform * point_it->point;
537 if (
ui_.color_transformer->currentIndex() ==
COLOR_Z)
544 const std::string& path)
549 node[
"topic"] >> topic;
550 ui_.topic->setText(boost::trim_copy(topic).c_str());
560 if (node[
"buffer_size"])
566 if (node[
"color_transformer"])
568 std::string color_transformer;
569 node[
"color_transformer"] >> color_transformer;
570 if (color_transformer ==
"Intensity")
572 else if (color_transformer ==
"Range")
574 else if (color_transformer ==
"X Axis")
575 ui_.color_transformer->setCurrentIndex(
COLOR_X);
576 else if (color_transformer ==
"Y Axis")
577 ui_.color_transformer->setCurrentIndex(
COLOR_Y);
578 else if (color_transformer ==
"Z Axis")
579 ui_.color_transformer->setCurrentIndex(
COLOR_Z);
584 if (node[
"min_color"])
586 std::string min_color_str;
587 node[
"min_color"] >> min_color_str;
588 ui_.min_color->setColor(QColor(min_color_str.c_str()));
591 if (node[
"max_color"])
593 std::string max_color_str;
594 node[
"max_color"] >> max_color_str;
595 ui_.max_color->setColor(QColor(max_color_str.c_str()));
598 if (node[
"value_min"])
604 if (node[
"max_value"])
616 if (node[
"use_rainbow"])
619 node[
"use_rainbow"] >> use_rainbow;
620 ui_.use_rainbow->setChecked(use_rainbow);
631 ROS_DEBUG(
"Color transformer changed to %d", index);
635 ui_.min_color->setVisible(
true);
636 ui_.max_color->setVisible(
false);
637 ui_.maxColorLabel->setVisible(
false);
638 ui_.minColorLabel->setVisible(
false);
639 ui_.minValueLabel->setVisible(
false);
640 ui_.maxValueLabel->setVisible(
false);
641 ui_.minValue->setVisible(
false);
642 ui_.maxValue->setVisible(
false);
643 ui_.use_rainbow->setVisible(
false);
651 ui_.min_color->setVisible(!
ui_.use_rainbow->isChecked());
652 ui_.max_color->setVisible(!
ui_.use_rainbow->isChecked());
653 ui_.maxColorLabel->setVisible(!
ui_.use_rainbow->isChecked());
654 ui_.minColorLabel->setVisible(!
ui_.use_rainbow->isChecked());
655 ui_.minValueLabel->setVisible(
true);
656 ui_.maxValueLabel->setVisible(
true);
657 ui_.minValue->setVisible(
true);
658 ui_.maxValue->setVisible(
true);
659 ui_.use_rainbow->setVisible(
true);
670 alpha_ = std::max(0.0
f, std::min((
float)val, 1.0
f));
674 const std::string& path)
676 emitter << YAML::Key <<
"topic" <<
677 YAML::Value << boost::trim_copy(
ui_.topic->text().toStdString());
678 emitter << YAML::Key <<
"size" <<
679 YAML::Value <<
ui_.pointSize->value();
680 emitter << YAML::Key <<
"buffer_size" <<
681 YAML::Value <<
ui_.bufferSize->value();
682 emitter << YAML::Key <<
"alpha" <<
684 emitter << YAML::Key <<
"color_transformer" <<
685 YAML::Value <<
ui_.color_transformer->currentText().toStdString();
686 emitter << YAML::Key <<
"min_color" <<
687 YAML::Value <<
ui_.min_color->color().name().toStdString();
688 emitter << YAML::Key <<
"max_color" <<
689 YAML::Value <<
ui_.max_color->color().name().toStdString();
690 emitter << YAML::Key <<
"value_min" <<
691 YAML::Value <<
ui_.minValue->text().toDouble();
692 emitter << YAML::Key <<
"value_max" <<
693 YAML::Value <<
ui_.maxValue->text().toDouble();
694 emitter << YAML::Key <<
"use_rainbow" <<
695 YAML::Value <<
ui_.use_rainbow->isChecked();