odometry_plugin.cpp
Go to the documentation of this file.
1 // *****************************************************************************
2 //
3 // Copyright (c) 2014, Southwest Research Institute® (SwRI®)
4 // All rights reserved.
5 //
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions are met:
8 // * Redistributions of source code must retain the above copyright
9 // notice, this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of Southwest Research Institute® (SwRI®) nor the
14 // names of its contributors may be used to endorse or promote products
15 // derived from this software without specific prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT HOLDER> BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //
28 // *****************************************************************************
29 
31 
32 // C++ standard libraries
33 #include <cstdio>
34 #include <vector>
35 
36 // QT libraries
37 #include <QDialog>
38 #include <QGLWidget>
39 #include <QPainter>
40 #include <QPalette>
41 
42 #include <opencv2/core/core.hpp>
43 
44 // ROS libraries
45 #include <ros/master.h>
46 
50 
51 // Declare plugin
54 
55 namespace mapviz_plugins
56 {
57  OdometryPlugin::OdometryPlugin() : config_widget_(new QWidget())
58  {
59  ui_.setupUi(config_widget_);
60  covariance_checked_ = ui_.show_covariance->isChecked();
61  ui_.color->setColor(Qt::green);
62 
63  // Set background white
64  QPalette p(config_widget_->palette());
65  p.setColor(QPalette::Background, Qt::white);
66  config_widget_->setPalette(p);
67 
68  // Set status text red
69  QPalette p3(ui_.status->palette());
70  p3.setColor(QPalette::Text, Qt::red);
71  ui_.status->setPalette(p3);
72 
73  QObject::connect(ui_.show_timestamps, SIGNAL(valueChanged(int)), this,
74  SLOT(TopicEditor()));
75  QObject::connect(ui_.selecttopic, SIGNAL(clicked()), this,
76  SLOT(SelectTopic()));
77  QObject::connect(ui_.topic, SIGNAL(editingFinished()), this,
78  SLOT(TopicEdited()));
79  QObject::connect(ui_.positiontolerance, SIGNAL(valueChanged(double)), this,
80  SLOT(PositionToleranceChanged(double)));
81  QObject::connect(ui_.buffersize, SIGNAL(valueChanged(int)), this,
82  SLOT(BufferSizeChanged(int)));
83  QObject::connect(ui_.drawstyle, SIGNAL(activated(QString)), this,
84  SLOT(SetDrawStyle(QString)));
85  QObject::connect(ui_.static_arrow_sizes, SIGNAL(clicked(bool)),
86  this, SLOT(SetStaticArrowSizes(bool)));
87  QObject::connect(ui_.arrow_size, SIGNAL(valueChanged(int)),
88  this, SLOT(SetArrowSize(int)));
89  connect(ui_.color, SIGNAL(colorEdited(const QColor&)), this,
90  SLOT(SetColor(const QColor&)));
91  }
92 
94  {
95  }
96 
98  {
100  mapviz::SelectTopicDialog::selectTopic("nav_msgs/Odometry");
101 
102  if (!topic.name.empty())
103  {
104  ui_.topic->setText(QString::fromStdString(topic.name));
105  TopicEdited();
106  }
107  }
108 
110  {
111  std::string topic = ui_.topic->text().trimmed().toStdString();
112  if (topic != topic_)
113  {
114  initialized_ = false;
115  points_.clear();
116  has_message_ = false;
117  PrintWarning("No messages received.");
118 
120 
121  topic_ = topic;
122  if (!topic.empty())
123  {
126 
127  ROS_INFO("Subscribing to %s", topic_.c_str());
128  }
129  }
130  }
131 
133  const nav_msgs::OdometryConstPtr odometry)
134  {
135  if (!has_message_)
136  {
137  initialized_ = true;
138  has_message_ = true;
139  }
140 
141  // Note that unlike some plugins, this one does not store nor rely on the
142  // source_frame_ member variable. This one can potentially store many
143  // messages with different source frames, so we need to store and transform
144  // them individually.
145  StampedPoint stamped_point;
146  stamped_point.stamp = odometry->header.stamp;
147  stamped_point.source_frame = odometry->header.frame_id;
148 
149  stamped_point.point = tf::Point(odometry->pose.pose.position.x,
150  odometry->pose.pose.position.y,
151  odometry->pose.pose.position.z);
152 
153  stamped_point.orientation = tf::Quaternion(
154  odometry->pose.pose.orientation.x,
155  odometry->pose.pose.orientation.y,
156  odometry->pose.pose.orientation.z,
157  odometry->pose.pose.orientation.w);
158 
159  if (points_.empty() ||
160  stamped_point.point.distance(points_.back().point) >=
162  {
163  points_.push_back(stamped_point);
164  }
165 
166  if (buffer_size_ > 0)
167  {
168  while (static_cast<int>(points_.size()) > buffer_size_)
169  {
170  points_.pop_front();
171  }
172  }
173 
174  cur_point_ = stamped_point;
175  covariance_checked_ = ui_.show_covariance->isChecked();
176  lap_checked_ = ui_.show_laps->isChecked();
177 
179  {
180  tf::Matrix3x3 tf_cov =
181  swri_transform_util::GetUpperLeft(odometry->pose.covariance);
182 
183  if (tf_cov[0][0] < 100000 && tf_cov[1][1] < 100000)
184  {
185  cv::Mat cov_matrix_3d(3, 3, CV_32FC1);
186  for (int32_t r = 0; r < 3; r++)
187  {
188  for (int32_t c = 0; c < 3; c++)
189  {
190  cov_matrix_3d.at<float>(r, c) = tf_cov[r][c];
191  }
192  }
193 
194  cv::Mat cov_matrix_2d =
195  swri_image_util::ProjectEllipsoid(cov_matrix_3d);
196 
197  if (!cov_matrix_2d.empty())
198  {
200  cov_matrix_2d, cur_point_.point, 3, 32);
201 
203  }
204  else
205  {
206  ROS_ERROR("Failed to project x, y, z covariance to xy-plane.");
207  }
208  }
209  }
210  }
211 
212  void OdometryPlugin::PrintError(const std::string& message)
213  {
214  PrintErrorHelper(ui_.status, message);
215  }
216 
217  void OdometryPlugin::PrintInfo(const std::string& message)
218  {
219  PrintInfoHelper(ui_.status, message);
220  }
221 
222  void OdometryPlugin::PrintWarning(const std::string& message)
223  {
224  PrintWarningHelper(ui_.status, message);
225  }
226 
227  QWidget* OdometryPlugin::GetConfigWidget(QWidget* parent)
228  {
229  config_widget_->setParent(parent);
230 
231  return config_widget_;
232  }
233 
234  bool OdometryPlugin::Initialize(QGLWidget* canvas)
235  {
236  canvas_ = canvas;
237  SetColor(ui_.color->color());
238 
239  return true;
240  }
241 
242  void OdometryPlugin::Draw(double x, double y, double scale)
243  {
244  if (ui_.show_covariance->isChecked())
245  {
246  DrawCovariance();
247  }
248  if (DrawPoints(scale))
249  {
250  PrintInfo("OK");
251  }
252  }
253 
254 
255  void OdometryPlugin::Paint(QPainter* painter, double x, double y, double scale)
256  {
257  //dont render any timestamps if the show_timestamps is set to 0
258  int interval = ui_.show_timestamps->value();
259  if (interval == 0)
260  {
261  return;
262  }
263 
264  QTransform tf = painter->worldTransform();
265  QFont font("Helvetica", 10);
266  painter->setFont(font);
267  painter->save();
268  painter->resetTransform();
269 
270  //set the draw color for the text to be the same as the rest
271  QPen pen(QBrush(ui_.color->color()), 1);
272  painter->setPen(pen);
273 
274  std::list<StampedPoint>::iterator it = points_.begin();
275  int counter = 0;//used to alternate between rendering text on some points
276  for (; it != points_.end(); ++it)
277  {
278  if (it->transformed && counter % interval == 0)//this renders a timestamp every 'interval' points
279  {
280  QPointF point = tf.map(QPointF(it->transformed_point.getX(),
281  it->transformed_point.getY()));
282  QString time;
283  time.setNum(it->stamp.toSec(), 'g', 12);
284  painter->drawText(point, time);
285  }
286  counter++;
287  }
288 
289  painter->restore();
290  }
291 
293  {
294  glLineWidth(4);
295 
296  glColor4d(color_.redF(), color_.greenF(), color_.blueF(), 1.0);
297 
299  {
300  glBegin(GL_LINE_STRIP);
301 
302  for (uint32_t i = 0; i < cur_point_.transformed_cov_points.size(); i++)
303  {
304  glVertex2d(cur_point_.transformed_cov_points[i].getX(),
306  }
307 
308  glVertex2d(cur_point_.transformed_cov_points.front().getX(),
309  cur_point_.transformed_cov_points.front().getY());
310 
311  glEnd();
312  }
313  }
314 
315  void OdometryPlugin::LoadConfig(const YAML::Node& node,
316  const std::string& path)
317  {
318  if (node["topic"])
319  {
320  std::string topic;
321  node["topic"] >> topic;
322  ui_.topic->setText(topic.c_str());
323  }
324 
325  if (node["color"])
326  {
327  std::string color;
328  node["color"] >> color;
329  SetColor(QColor(color.c_str()));
330  ui_.color->setColor(color_);
331  }
332 
333  if (node["draw_style"])
334  {
335  std::string draw_style;
336  node["draw_style"] >> draw_style;
337 
338  if (draw_style == "lines")
339  {
340  draw_style_ = LINES;
341  ui_.drawstyle->setCurrentIndex(0);
342  }
343  else if (draw_style == "points")
344  {
346  ui_.drawstyle->setCurrentIndex(1);
347  }
348  else if (draw_style == "arrows")
349  {
351  ui_.drawstyle->setCurrentIndex(2);
352  }
353  }
354 
355  if (node["position_tolerance"])
356  {
357  node["position_tolerance"] >> position_tolerance_;
358  ui_.positiontolerance->setValue(position_tolerance_);
359  }
360 
361  if (node["buffer_size"])
362  {
363  node["buffer_size"] >> buffer_size_;
364  ui_.buffersize->setValue(buffer_size_);
365  }
366 
367  if (node["show_covariance"])
368  {
369  bool show_covariance = false;
370  node["show_covariance"] >> show_covariance;
371  ui_.show_covariance->setChecked(show_covariance);
372  }
373  if (node["show_laps"])
374  {
375  bool show_laps = false;
376  node["show_laps"] >> show_laps;
377  ui_.show_laps->setChecked(show_laps);
378  }
379 
380  if (node["static_arrow_sizes"])
381  {
382  bool static_arrow_sizes = node["static_arrow_sizes"].as<bool>();
383  ui_.static_arrow_sizes->setChecked(static_arrow_sizes);
384  SetStaticArrowSizes(static_arrow_sizes);
385  }
386 
387  if (node["arrow_size"])
388  {
389  ui_.arrow_size->setValue(node["arrow_size"].as<int>());
390  }
391 
392  if (node["show_timestamps"])
393  {
394  ui_.show_timestamps->setValue(node["show_timestamps"].as<int>());
395  }
396 
397  TopicEdited();
398  }
399 
400  void OdometryPlugin::SaveConfig(YAML::Emitter& emitter,
401  const std::string& path)
402  {
403  std::string topic = ui_.topic->text().toStdString();
404  emitter << YAML::Key << "topic" << YAML::Value << topic;
405 
406  std::string color = ui_.color->color().name().toStdString();
407  emitter << YAML::Key << "color" << YAML::Value << color;
408 
409  std::string draw_style = ui_.drawstyle->currentText().toStdString();
410  emitter << YAML::Key << "draw_style" << YAML::Value << draw_style;
411 
412  emitter << YAML::Key << "position_tolerance" <<
413  YAML::Value << position_tolerance_;
414  if (!lap_checked_)
415  {
416  emitter << YAML::Key << "buffer_size" << YAML::Value << buffer_size_;
417  }
418  else
419  {
420  emitter << YAML::Key << "buffer_size" << YAML::Value << buffer_holder_;
421  }
422  bool show_laps = ui_.show_laps->isChecked();
423  emitter << YAML::Key << "show_laps" << YAML::Value << show_laps;
424 
425  bool show_covariance = ui_.show_covariance->isChecked();
426  emitter << YAML::Key << "show_covariance" << YAML::Value << show_covariance;
427 
428  emitter << YAML::Key << "static_arrow_sizes" << YAML::Value << ui_.static_arrow_sizes->isChecked();
429 
430  emitter << YAML::Key << "arrow_size" << YAML::Value << ui_.arrow_size->value();
431 
432  emitter << YAML::Key << "show_timestamps" << YAML::Value << ui_.show_timestamps->value();
433  }
434 }
435 
436 
bool Initialize(QGLWidget *canvas)
cv::Mat ProjectEllipsoid(const cv::Mat &ellipsiod)
static ros::master::TopicInfo selectTopic(const std::string &datatype, QWidget *parent=0)
void Draw(double x, double y, double scale)
ros::NodeHandle node_
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())
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)
tf::Vector3 Point
void odometryCallback(const nav_msgs::OdometryConstPtr odometry)
TFSIMD_FORCE_INLINE tfScalar distance(const Vector3 &v) const
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)
#define ROS_INFO(...)
tf::Matrix3x3 GetUpperLeft(const boost::array< double, 36 > &matrix)
std::vector< tf::Vector3 > GetEllipsePoints(const cv::Mat &ellipse, const tf::Vector3 &center, double scale, int32_t num_points)
virtual void SetColor(const QColor &color)
virtual void SetStaticArrowSizes(bool isChecked)
void PrintInfo(const std::string &message)
virtual void SetDrawStyle(QString style)
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
#define ROS_ERROR(...)
void LoadConfig(const YAML::Node &node, const std::string &path)


mapviz_plugins
Author(s): Marc Alban
autogenerated on Thu Jun 6 2019 19:25:16