31 #include <opencv2/core/core.hpp>
51 ui_.color->setColor(Qt::green);
55 p.setColor(QPalette::Background, Qt::white);
59 QPalette p3(
ui_.status->palette());
60 p3.setColor(QPalette::Text, Qt::red);
61 ui_.status->setPalette(p3);
63 QObject::connect(
ui_.selecttopic, SIGNAL(clicked()),
this,
65 QObject::connect(
ui_.topic, SIGNAL(editingFinished()),
this,
67 QObject::connect(
ui_.use_latest_transforms, SIGNAL(clicked(
bool)),
69 QObject::connect(
ui_.positiontolerance, SIGNAL(valueChanged(
double)),
this,
71 QObject::connect(
ui_.buffersize, SIGNAL(valueChanged(
int)),
this,
73 QObject::connect(
ui_.drawstyle, SIGNAL(activated(QString)),
this,
75 QObject::connect(
ui_.color, SIGNAL(colorEdited(
const QColor&)),
this,
77 QObject::connect(
ui_.buttonResetBuffer, SIGNAL(pressed()),
this,
90 if (!topic.
name.empty())
92 ui_.topic->setText(QString::fromStdString(topic.
name));
99 std::string topic =
ui_.topic->text().trimmed().toStdString();
119 const sensor_msgs::NavSatFixConstPtr navsat)
132 stamped_point.
stamp = navsat->header.stamp;
136 tf_manager_->LocalXyUtil()->ToLocalXy(navsat->latitude, navsat->longitude, x, y);
187 node[
"topic"] >> topic;
188 ui_.topic->setText(topic.c_str());
194 node[
"color"] >> color;
195 QColor qcolor(color.c_str());
197 ui_.color->setColor(qcolor);
200 if (node[
"draw_style"])
202 std::string draw_style;
203 node[
"draw_style"] >> draw_style;
205 if (draw_style ==
"lines")
207 ui_.drawstyle->setCurrentIndex(0);
210 else if (draw_style ==
"points")
212 ui_.drawstyle->setCurrentIndex(1);
217 if (node[
"use_latest_transforms"])
219 bool use_latest_transforms = node[
"use_latest_transforms"].as<
bool>();
220 ui_.use_latest_transforms->setChecked(use_latest_transforms);
224 if (node[
"position_tolerance"])
226 double position_tolerance;
227 node[
"position_tolerance"] >> position_tolerance;
228 ui_.positiontolerance->setValue(position_tolerance);
232 if (node[
"buffer_size"])
235 node[
"buffer_size"] >> buffer_size;
236 ui_.buffersize->setValue(buffer_size);
245 std::string topic =
ui_.topic->text().toStdString();
246 emitter << YAML::Key <<
"topic" << YAML::Value << topic;
248 std::string color =
ui_.color->color().name().toStdString();
249 emitter << YAML::Key <<
"color" << YAML::Value << color;
251 std::string draw_style =
ui_.drawstyle->currentText().toStdString();
252 emitter << YAML::Key <<
"draw_style" << YAML::Value << draw_style;
254 emitter << YAML::Key <<
"use_latest_transforms" << YAML::Value <<
ui_.use_latest_transforms->isChecked();
256 emitter << YAML::Key <<
"position_tolerance" <<
259 emitter << YAML::Key <<
"buffer_size" << YAML::Value <<
bufferSize();