42 #include <opencv2/core/core.hpp> 57 OdometryPlugin::OdometryPlugin() : config_widget_(new QWidget())
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_.arrow_size, SIGNAL(valueChanged(
int)),
86 QObject::connect(
ui_.color, SIGNAL(colorEdited(
const QColor&)),
this,
88 QObject::connect(
ui_.show_laps, SIGNAL(toggled(
bool)),
this,
90 QObject::connect(
ui_.show_covariance, SIGNAL(toggled(
bool)),
this,
92 QObject::connect(
ui_.show_all_covariances, SIGNAL(toggled(
bool)),
this,
94 QObject::connect(
ui_.buttonResetBuffer, SIGNAL(pressed()),
this,
107 if (!topic.
name.empty())
109 ui_.topic->setText(QString::fromStdString(topic.
name));
116 std::string topic =
ui_.topic->text().trimmed().toStdString();
138 const nav_msgs::OdometryConstPtr odometry)
151 stamped_point.
stamp = odometry->header.stamp;
155 odometry->pose.pose.position.y,
156 odometry->pose.pose.position.z);
159 odometry->pose.pose.orientation.x,
160 odometry->pose.pose.orientation.y,
161 odometry->pose.pose.orientation.z,
162 odometry->pose.pose.orientation.w);
164 if (
ui_.show_covariance->isChecked() )
169 if (tf_cov[0][0] < 100000 && tf_cov[1][1] < 100000)
171 cv::Mat cov_matrix_3d(3, 3, CV_32FC1);
172 for (int32_t r = 0; r < 3; r++)
174 for (int32_t c = 0; c < 3; c++)
176 cov_matrix_3d.at<
float>(r, c) = tf_cov[r][c];
182 if (!cov_matrix_2d.empty())
185 cov_matrix_2d, stamped_point.
point, 3, 32);
191 ROS_ERROR(
"Failed to project x, y, z covariance to xy-plane.");
232 if (
ui_.show_covariance->isChecked())
246 int interval =
ui_.show_timestamps->value();
252 QTransform
tf = painter->worldTransform();
253 QFont font(
"Helvetica", 10);
254 painter->setFont(font);
256 painter->resetTransform();
259 QPen pen(QBrush(
ui_.color->color()), 1);
260 painter->setPen(pen);
265 if (point.transformed && counter % interval == 0)
267 QPointF qpoint = tf.map(QPointF(point.transformed_point.getX(),
268 point.transformed_point.getY()));
270 time.setNum(point.stamp.toSec(),
'g', 12);
271 painter->drawText(qpoint, time);
280 const std::string& path)
285 node[
"topic"] >> topic;
286 ui_.topic->setText(topic.c_str());
292 node[
"color"] >> color;
293 QColor qcolor(color.c_str());
295 ui_.color->setColor(qcolor);
298 if (node[
"draw_style"])
300 std::string draw_style;
301 node[
"draw_style"] >> draw_style;
303 if (draw_style ==
"lines")
305 ui_.drawstyle->setCurrentIndex(0);
308 else if (draw_style ==
"points")
310 ui_.drawstyle->setCurrentIndex(1);
313 else if (draw_style ==
"arrows")
315 ui_.drawstyle->setCurrentIndex(2);
320 if (node[
"position_tolerance"])
322 double position_tolerance;
323 node[
"position_tolerance"] >> position_tolerance;
324 ui_.positiontolerance->setValue(position_tolerance);
328 if (node[
"buffer_size"])
331 node[
"buffer_size"] >> buffer_size;
332 ui_.buffersize->setValue(buffer_size);
336 if (node[
"show_covariance"])
338 bool show_covariance =
false;
339 node[
"show_covariance"] >> show_covariance;
340 ui_.show_covariance->setChecked(show_covariance);
344 if (node[
"show_all_covariances"])
346 bool show_all_covariances =
false;
347 node[
"show_all_covariances"] >> show_all_covariances;
348 ui_.show_all_covariances->setChecked(show_all_covariances);
352 if (node[
"show_laps"])
354 bool show_laps =
false;
355 node[
"show_laps"] >> show_laps;
356 ui_.show_laps->setChecked(show_laps);
360 if (node[
"static_arrow_sizes"])
362 bool static_arrow_sizes = node[
"static_arrow_sizes"].as<
bool>();
363 ui_.static_arrow_sizes->setChecked(static_arrow_sizes);
367 if (node[
"arrow_size"])
369 double arrow_size = node[
"arrow_size"].as<
int>();
370 ui_.arrow_size->setValue(arrow_size);
374 if (node[
"show_timestamps"])
376 ui_.show_timestamps->setValue(node[
"show_timestamps"].as<int>());
383 const std::string& path)
385 std::string topic =
ui_.topic->text().toStdString();
386 emitter << YAML::Key <<
"topic" << YAML::Value << topic;
388 std::string color =
ui_.color->color().name().toStdString();
389 emitter << YAML::Key <<
"color" << YAML::Value << color;
391 std::string draw_style =
ui_.drawstyle->currentText().toStdString();
392 emitter << YAML::Key <<
"draw_style" << YAML::Value << draw_style;
394 emitter << YAML::Key <<
"position_tolerance" <<
397 emitter << YAML::Key <<
"buffer_size" << YAML::Value <<
bufferSize();
399 bool show_laps =
ui_.show_laps->isChecked();
400 emitter << YAML::Key <<
"show_laps" << YAML::Value << show_laps;
402 bool show_covariance =
ui_.show_covariance->isChecked();
403 emitter << YAML::Key <<
"show_covariance" << YAML::Value << show_covariance;
405 bool show_all_covariances =
ui_.show_all_covariances->isChecked();
406 emitter << YAML::Key <<
"show_all_covariances" << YAML::Value << show_all_covariances;
408 emitter << YAML::Key <<
"static_arrow_sizes" << YAML::Value <<
ui_.static_arrow_sizes->isChecked();
410 emitter << YAML::Key <<
"arrow_size" << YAML::Value <<
ui_.arrow_size->value();
412 emitter << YAML::Key <<
"show_timestamps" << YAML::Value <<
ui_.show_timestamps->value();
bool Initialize(QGLWidget *canvas)
std::vector< tf::Point > cov_points
cv::Mat ProjectEllipsoid(const cv::Mat &ellipsiod)
double positionTolerance() const
static ros::master::TopicInfo selectTopic(const std::string &datatype, QWidget *parent=0)
void Draw(double x, double y, double scale)
virtual void DrawCovariance()
virtual void PositionToleranceChanged(double value)
virtual void SetArrowSize(int arrowSize)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::Subscriber odometry_sub_
virtual bool DrawPoints(double scale)
static void PrintWarningHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
static void PrintErrorHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
void PrintError(const std::string &message)
void odometryCallback(const nav_msgs::OdometryConstPtr odometry)
static void PrintInfoHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
void Paint(QPainter *painter, double x, double y, double scale)
QWidget * GetConfigWidget(QWidget *parent)
void PrintWarning(const std::string &message)
std::vector< tf::Vector3 > GetEllipsePoints(const cv::Mat &ellipse, const tf::Vector3 ¢er, double scale, int32_t num_points)
virtual void BufferSizeChanged(int value)
virtual void LapToggled(bool checked)
virtual void SetColor(const QColor &color)
virtual void SetStaticArrowSizes(bool isChecked)
std::vector< tf::Point > transformed_cov_points
virtual void ShowAllCovariancesToggled(bool checked)
double bufferSize() const
const std::deque< StampedPoint > & points() const
virtual void CovariancedToggled(bool checked)
void PrintInfo(const std::string &message)
void pushPoint(StampedPoint point)
virtual void SetDrawStyle(QString style)
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
tf::Quaternion orientation
void LoadConfig(const YAML::Node &node, const std::string &path)
virtual ~OdometryPlugin()