42 #include <opencv2/core/core.hpp>
60 ui_.color->setColor(Qt::green);
64 p.setColor(QPalette::Background, Qt::white);
68 QPalette p3(
ui_.status->palette());
69 p3.setColor(QPalette::Text, Qt::red);
70 ui_.status->setPalette(p3);
72 QObject::connect(
ui_.selecttopic, SIGNAL(clicked()),
this,
74 QObject::connect(
ui_.topic, SIGNAL(editingFinished()),
this,
76 QObject::connect(
ui_.positiontolerance, SIGNAL(valueChanged(
double)),
this,
78 QObject::connect(
ui_.buffersize, SIGNAL(valueChanged(
int)),
this,
80 QObject::connect(
ui_.drawstyle, SIGNAL(activated(QString)),
this,
82 QObject::connect(
ui_.static_arrow_sizes, SIGNAL(clicked(
bool)),
84 QObject::connect(
ui_.use_latest_transforms, SIGNAL(clicked(
bool)),
86 QObject::connect(
ui_.arrow_size, SIGNAL(valueChanged(
int)),
88 QObject::connect(
ui_.color, SIGNAL(colorEdited(
const QColor&)),
this,
90 QObject::connect(
ui_.show_laps, SIGNAL(toggled(
bool)),
this,
92 QObject::connect(
ui_.show_covariance, SIGNAL(toggled(
bool)),
this,
94 QObject::connect(
ui_.show_all_covariances, SIGNAL(toggled(
bool)),
this,
96 QObject::connect(
ui_.buttonResetBuffer, SIGNAL(pressed()),
this,
109 if (!topic.
name.empty())
111 ui_.topic->setText(QString::fromStdString(topic.
name));
118 std::string topic =
ui_.topic->text().trimmed().toStdString();
140 const nav_msgs::OdometryConstPtr odometry)
153 stamped_point.
stamp = odometry->header.stamp;
162 odometry->pose.pose.position.y,
163 odometry->pose.pose.position.z);
166 odometry->pose.pose.orientation.x,
167 odometry->pose.pose.orientation.y,
168 odometry->pose.pose.orientation.z,
169 odometry->pose.pose.orientation.w);
171 if (
ui_.show_covariance->isChecked() )
176 if (tf_cov[0][0] < 100000 && tf_cov[1][1] < 100000)
178 cv::Mat cov_matrix_3d(3, 3, CV_32FC1);
179 for (int32_t r = 0; r < 3; r++)
181 for (int32_t c = 0; c < 3; c++)
183 cov_matrix_3d.at<
float>(r, c) = tf_cov[r][c];
189 if (!cov_matrix_2d.empty())
192 cov_matrix_2d, stamped_point.
point, 3, 32);
198 ROS_ERROR(
"Failed to project x, y, z covariance to xy-plane.");
239 if (
ui_.show_covariance->isChecked())
253 int interval =
ui_.show_timestamps->value();
259 QTransform
tf = painter->worldTransform();
260 QFont font(
"Helvetica", 10);
261 painter->setFont(font);
263 painter->resetTransform();
266 QPen pen(QBrush(
ui_.color->color()), 1);
267 painter->setPen(pen);
272 if (point.transformed && counter % interval == 0)
274 QPointF qpoint =
tf.map(QPointF(point.transformed_point.getX(),
275 point.transformed_point.getY()));
277 time.setNum(point.stamp.toSec(),
'g', 12);
278 painter->drawText(qpoint, time);
287 const std::string& path)
292 node[
"topic"] >> topic;
293 ui_.topic->setText(topic.c_str());
299 node[
"color"] >> color;
300 QColor qcolor(color.c_str());
302 ui_.color->setColor(qcolor);
305 if (node[
"draw_style"])
307 std::string draw_style;
308 node[
"draw_style"] >> draw_style;
310 if (draw_style ==
"lines")
312 ui_.drawstyle->setCurrentIndex(0);
315 else if (draw_style ==
"points")
317 ui_.drawstyle->setCurrentIndex(1);
320 else if (draw_style ==
"arrows")
322 ui_.drawstyle->setCurrentIndex(2);
327 if (node[
"position_tolerance"])
329 double position_tolerance;
330 node[
"position_tolerance"] >> position_tolerance;
331 ui_.positiontolerance->setValue(position_tolerance);
335 if (node[
"buffer_size"])
338 node[
"buffer_size"] >> buffer_size;
339 ui_.buffersize->setValue(buffer_size);
343 if (node[
"show_covariance"])
345 bool show_covariance =
false;
346 node[
"show_covariance"] >> show_covariance;
347 ui_.show_covariance->setChecked(show_covariance);
351 if (node[
"show_all_covariances"])
353 bool show_all_covariances =
false;
354 node[
"show_all_covariances"] >> show_all_covariances;
355 ui_.show_all_covariances->setChecked(show_all_covariances);
359 if (node[
"show_laps"])
361 bool show_laps =
false;
362 node[
"show_laps"] >> show_laps;
363 ui_.show_laps->setChecked(show_laps);
367 if (node[
"static_arrow_sizes"])
369 bool static_arrow_sizes = node[
"static_arrow_sizes"].as<
bool>();
370 ui_.static_arrow_sizes->setChecked(static_arrow_sizes);
374 if (node[
"arrow_size"])
376 double arrow_size = node[
"arrow_size"].as<
int>();
377 ui_.arrow_size->setValue(arrow_size);
381 if (node[
"use_latest_transforms"])
383 bool use_latest_transforms = node[
"use_latest_transforms"].as<
bool>();
384 ui_.use_latest_transforms->setChecked(use_latest_transforms);
388 if (node[
"show_timestamps"])
390 ui_.show_timestamps->setValue(node[
"show_timestamps"].as<int>());
397 const std::string& path)
399 std::string topic =
ui_.topic->text().toStdString();
400 emitter << YAML::Key <<
"topic" << YAML::Value << topic;
402 std::string color =
ui_.color->color().name().toStdString();
403 emitter << YAML::Key <<
"color" << YAML::Value << color;
405 std::string draw_style =
ui_.drawstyle->currentText().toStdString();
406 emitter << YAML::Key <<
"draw_style" << YAML::Value << draw_style;
408 emitter << YAML::Key <<
"position_tolerance" <<
411 emitter << YAML::Key <<
"buffer_size" << YAML::Value <<
bufferSize();
413 bool show_laps =
ui_.show_laps->isChecked();
414 emitter << YAML::Key <<
"show_laps" << YAML::Value << show_laps;
416 bool show_covariance =
ui_.show_covariance->isChecked();
417 emitter << YAML::Key <<
"show_covariance" << YAML::Value << show_covariance;
419 bool show_all_covariances =
ui_.show_all_covariances->isChecked();
420 emitter << YAML::Key <<
"show_all_covariances" << YAML::Value << show_all_covariances;
422 emitter << YAML::Key <<
"static_arrow_sizes" << YAML::Value <<
ui_.static_arrow_sizes->isChecked();
424 emitter << YAML::Key <<
"arrow_size" << YAML::Value <<
ui_.arrow_size->value();
426 emitter << YAML::Key <<
"use_latest_transforms" << YAML::Value <<
ui_.use_latest_transforms->isChecked();
428 emitter << YAML::Key <<
"show_timestamps" << YAML::Value <<
ui_.show_timestamps->value();