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  ui_.color->setColor(Qt::green);
61 
62  // Set background white
63  QPalette p(config_widget_->palette());
64  p.setColor(QPalette::Background, Qt::white);
65  config_widget_->setPalette(p);
66 
67  // Set status text red
68  QPalette p3(ui_.status->palette());
69  p3.setColor(QPalette::Text, Qt::red);
70  ui_.status->setPalette(p3);
71 
72  QObject::connect(ui_.selecttopic, SIGNAL(clicked()), this,
73  SLOT(SelectTopic()));
74  QObject::connect(ui_.topic, SIGNAL(editingFinished()), this,
75  SLOT(TopicEdited()));
76  QObject::connect(ui_.positiontolerance, SIGNAL(valueChanged(double)), this,
77  SLOT(PositionToleranceChanged(double)));
78  QObject::connect(ui_.buffersize, SIGNAL(valueChanged(int)), this,
79  SLOT(BufferSizeChanged(int)));
80  QObject::connect(ui_.drawstyle, SIGNAL(activated(QString)), this,
81  SLOT(SetDrawStyle(QString)));
82  QObject::connect(ui_.static_arrow_sizes, SIGNAL(clicked(bool)),
83  this, SLOT(SetStaticArrowSizes(bool)));
84  QObject::connect(ui_.use_latest_transforms, SIGNAL(clicked(bool)),
85  this, SLOT(SetUseLatestTransforms(bool)));
86  QObject::connect(ui_.arrow_size, SIGNAL(valueChanged(int)),
87  this, SLOT(SetArrowSize(int)));
88  QObject::connect(ui_.color, SIGNAL(colorEdited(const QColor&)), this,
89  SLOT(SetColor(const QColor&)));
90  QObject::connect(ui_.show_laps, SIGNAL(toggled(bool)), this,
91  SLOT(LapToggled(bool)));
92  QObject::connect(ui_.show_covariance, SIGNAL(toggled(bool)), this,
93  SLOT(CovariancedToggled(bool)));
94  QObject::connect(ui_.show_all_covariances, SIGNAL(toggled(bool)), this,
95  SLOT(ShowAllCovariancesToggled(bool)));
96  QObject::connect(ui_.buttonResetBuffer, SIGNAL(pressed()), this,
97  SLOT(ClearPoints()));
98  }
99 
101  {
102  }
103 
105  {
106  ros::master::TopicInfo topic =
107  mapviz::SelectTopicDialog::selectTopic("nav_msgs/Odometry");
108 
109  if (!topic.name.empty())
110  {
111  ui_.topic->setText(QString::fromStdString(topic.name));
112  TopicEdited();
113  }
114  }
115 
117  {
118  std::string topic = ui_.topic->text().trimmed().toStdString();
119  if (topic != topic_)
120  {
121  initialized_ = false;
122  ClearPoints();
123  has_message_ = false;
124  PrintWarning("No messages received.");
125 
127 
128  topic_ = topic;
129  if (!topic.empty())
130  {
133 
134  ROS_INFO("Subscribing to %s", topic_.c_str());
135  }
136  }
137  }
138 
140  const nav_msgs::OdometryConstPtr odometry)
141  {
142  if (!has_message_)
143  {
144  initialized_ = true;
145  has_message_ = true;
146  }
147 
148  // Note that unlike some plugins, this one does not store nor rely on the
149  // source_frame_ member variable. This one can potentially store many
150  // messages with different source frames, so we need to store and transform
151  // them individually.
152  StampedPoint stamped_point;
153  stamped_point.stamp = odometry->header.stamp;
154  stamped_point.source_frame = odometry->header.frame_id;
155 
156  if (!points().empty() && points().back().source_frame != stamped_point.source_frame)
157  {
158  single_frame_ = false;
159  }
160 
161  stamped_point.point = tf::Point(odometry->pose.pose.position.x,
162  odometry->pose.pose.position.y,
163  odometry->pose.pose.position.z);
164 
165  stamped_point.orientation = tf::Quaternion(
166  odometry->pose.pose.orientation.x,
167  odometry->pose.pose.orientation.y,
168  odometry->pose.pose.orientation.z,
169  odometry->pose.pose.orientation.w);
170 
171  if ( ui_.show_covariance->isChecked() )
172  {
173  tf::Matrix3x3 tf_cov =
174  swri_transform_util::GetUpperLeft(odometry->pose.covariance);
175 
176  if (tf_cov[0][0] < 100000 && tf_cov[1][1] < 100000)
177  {
178  cv::Mat cov_matrix_3d(3, 3, CV_32FC1);
179  for (int32_t r = 0; r < 3; r++)
180  {
181  for (int32_t c = 0; c < 3; c++)
182  {
183  cov_matrix_3d.at<float>(r, c) = tf_cov[r][c];
184  }
185  }
186 
187  cv::Mat cov_matrix_2d = swri_image_util::ProjectEllipsoid(cov_matrix_3d);
188 
189  if (!cov_matrix_2d.empty())
190  {
192  cov_matrix_2d, stamped_point.point, 3, 32);
193 
194  stamped_point.transformed_cov_points = stamped_point.cov_points;
195  }
196  else
197  {
198  ROS_ERROR("Failed to project x, y, z covariance to xy-plane.");
199  }
200  }
201  }
202 
203  pushPoint( std::move(stamped_point) );
204 
205  }
206 
207  void OdometryPlugin::PrintError(const std::string& message)
208  {
209  PrintErrorHelper(ui_.status, message);
210  }
211 
212  void OdometryPlugin::PrintInfo(const std::string& message)
213  {
214  PrintInfoHelper(ui_.status, message);
215  }
216 
217  void OdometryPlugin::PrintWarning(const std::string& message)
218  {
219  PrintWarningHelper(ui_.status, message);
220  }
221 
222  QWidget* OdometryPlugin::GetConfigWidget(QWidget* parent)
223  {
224  config_widget_->setParent(parent);
225 
226  return config_widget_;
227  }
228 
229  bool OdometryPlugin::Initialize(QGLWidget* canvas)
230  {
231  canvas_ = canvas;
232  SetColor(ui_.color->color());
233 
234  return true;
235  }
236 
237  void OdometryPlugin::Draw(double x, double y, double scale)
238  {
239  if (ui_.show_covariance->isChecked())
240  {
241  DrawCovariance();
242  }
243  if (DrawPoints(scale))
244  {
245  PrintInfo("OK");
246  }
247  }
248 
249 
250  void OdometryPlugin::Paint(QPainter* painter, double x, double y, double scale)
251  {
252  //dont render any timestamps if the show_timestamps is set to 0
253  int interval = ui_.show_timestamps->value();
254  if (interval == 0)
255  {
256  return;
257  }
258 
259  QTransform tf = painter->worldTransform();
260  QFont font("Helvetica", 10);
261  painter->setFont(font);
262  painter->save();
263  painter->resetTransform();
264 
265  //set the draw color for the text to be the same as the rest
266  QPen pen(QBrush(ui_.color->color()), 1);
267  painter->setPen(pen);
268 
269  int counter = 0;//used to alternate between rendering text on some points
270  for (const StampedPoint& point: points())
271  {
272  if (point.transformed && counter % interval == 0)//this renders a timestamp every 'interval' points
273  {
274  QPointF qpoint = tf.map(QPointF(point.transformed_point.getX(),
275  point.transformed_point.getY()));
276  QString time;
277  time.setNum(point.stamp.toSec(), 'g', 12);
278  painter->drawText(qpoint, time);
279  }
280  counter++;
281  }
282 
283  painter->restore();
284  }
285 
286  void OdometryPlugin::LoadConfig(const YAML::Node& node,
287  const std::string& path)
288  {
289  if (node["topic"])
290  {
291  std::string topic;
292  node["topic"] >> topic;
293  ui_.topic->setText(topic.c_str());
294  }
295 
296  if (node["color"])
297  {
298  std::string color;
299  node["color"] >> color;
300  QColor qcolor(color.c_str());
301  SetColor(qcolor);
302  ui_.color->setColor(qcolor);
303  }
304 
305  if (node["draw_style"])
306  {
307  std::string draw_style;
308  node["draw_style"] >> draw_style;
309 
310  if (draw_style == "lines")
311  {
312  ui_.drawstyle->setCurrentIndex(0);
313  SetDrawStyle( LINES );
314  }
315  else if (draw_style == "points")
316  {
317  ui_.drawstyle->setCurrentIndex(1);
318  SetDrawStyle( POINTS );
319  }
320  else if (draw_style == "arrows")
321  {
322  ui_.drawstyle->setCurrentIndex(2);
323  SetDrawStyle( ARROWS );
324  }
325  }
326 
327  if (node["position_tolerance"])
328  {
329  double position_tolerance;
330  node["position_tolerance"] >> position_tolerance;
331  ui_.positiontolerance->setValue(position_tolerance);
332  PositionToleranceChanged(position_tolerance);
333  }
334 
335  if (node["buffer_size"])
336  {
337  double buffer_size;
338  node["buffer_size"] >> buffer_size;
339  ui_.buffersize->setValue(buffer_size);
340  BufferSizeChanged(buffer_size);
341  }
342 
343  if (node["show_covariance"])
344  {
345  bool show_covariance = false;
346  node["show_covariance"] >> show_covariance;
347  ui_.show_covariance->setChecked(show_covariance);
348  CovariancedToggled(show_covariance);
349  }
350 
351  if (node["show_all_covariances"])
352  {
353  bool show_all_covariances = false;
354  node["show_all_covariances"] >> show_all_covariances;
355  ui_.show_all_covariances->setChecked(show_all_covariances);
356  ShowAllCovariancesToggled(show_all_covariances);
357  }
358 
359  if (node["show_laps"])
360  {
361  bool show_laps = false;
362  node["show_laps"] >> show_laps;
363  ui_.show_laps->setChecked(show_laps);
364  LapToggled(show_laps);
365  }
366 
367  if (node["static_arrow_sizes"])
368  {
369  bool static_arrow_sizes = node["static_arrow_sizes"].as<bool>();
370  ui_.static_arrow_sizes->setChecked(static_arrow_sizes);
371  SetStaticArrowSizes(static_arrow_sizes);
372  }
373 
374  if (node["arrow_size"])
375  {
376  double arrow_size = node["arrow_size"].as<int>();
377  ui_.arrow_size->setValue(arrow_size);
378  SetArrowSize(arrow_size);
379  }
380 
381  if (node["use_latest_transforms"])
382  {
383  bool use_latest_transforms = node["use_latest_transforms"].as<bool>();
384  ui_.use_latest_transforms->setChecked(use_latest_transforms);
385  SetUseLatestTransforms(use_latest_transforms);
386  }
387 
388  if (node["show_timestamps"])
389  {
390  ui_.show_timestamps->setValue(node["show_timestamps"].as<int>());
391  }
392 
393  TopicEdited();
394  }
395 
396  void OdometryPlugin::SaveConfig(YAML::Emitter& emitter,
397  const std::string& path)
398  {
399  std::string topic = ui_.topic->text().toStdString();
400  emitter << YAML::Key << "topic" << YAML::Value << topic;
401 
402  std::string color = ui_.color->color().name().toStdString();
403  emitter << YAML::Key << "color" << YAML::Value << color;
404 
405  std::string draw_style = ui_.drawstyle->currentText().toStdString();
406  emitter << YAML::Key << "draw_style" << YAML::Value << draw_style;
407 
408  emitter << YAML::Key << "position_tolerance" <<
409  YAML::Value << positionTolerance();
410 
411  emitter << YAML::Key << "buffer_size" << YAML::Value << bufferSize();
412 
413  bool show_laps = ui_.show_laps->isChecked();
414  emitter << YAML::Key << "show_laps" << YAML::Value << show_laps;
415 
416  bool show_covariance = ui_.show_covariance->isChecked();
417  emitter << YAML::Key << "show_covariance" << YAML::Value << show_covariance;
418 
419  bool show_all_covariances = ui_.show_all_covariances->isChecked();
420  emitter << YAML::Key << "show_all_covariances" << YAML::Value << show_all_covariances;
421 
422  emitter << YAML::Key << "static_arrow_sizes" << YAML::Value << ui_.static_arrow_sizes->isChecked();
423 
424  emitter << YAML::Key << "arrow_size" << YAML::Value << ui_.arrow_size->value();
425 
426  emitter << YAML::Key << "use_latest_transforms" << YAML::Value << ui_.use_latest_transforms->isChecked();
427 
428  emitter << YAML::Key << "show_timestamps" << YAML::Value << ui_.show_timestamps->value();
429  }
430 }
431 
432 
tf::Matrix3x3
mapviz_plugins::PointDrawingPlugin::CovariancedToggled
virtual void CovariancedToggled(bool checked)
Definition: point_drawing_plugin.cpp:165
swri_image_util::GetEllipsePoints
std::vector< tf::Vector3 > GetEllipsePoints(const cv::Mat &ellipse, const tf::Vector3 &center, double scale, int32_t num_points)
mapviz_plugins::PointDrawingPlugin::StampedPoint
Definition: point_drawing_plugin.h:56
mapviz_plugins::PointDrawingPlugin::LapToggled
virtual void LapToggled(bool checked)
Definition: point_drawing_plugin.cpp:160
mapviz_plugins::OdometryPlugin::GetConfigWidget
QWidget * GetConfigWidget(QWidget *parent)
Definition: odometry_plugin.cpp:222
select_topic_dialog.h
mapviz_plugins::OdometryPlugin::topic_
std::string topic_
Definition: odometry_plugin.h:96
mapviz_plugins::PointDrawingPlugin::DrawPoints
virtual bool DrawPoints(double scale)
Definition: point_drawing_plugin.cpp:258
mapviz_plugins::PointDrawingPlugin::ClearPoints
void ClearPoints()
Definition: point_drawing_plugin.cpp:218
mapviz_plugins::OdometryPlugin::PrintWarning
void PrintWarning(const std::string &message)
Definition: odometry_plugin.cpp:217
mapviz_plugins::OdometryPlugin::SelectTopic
void SelectTopic()
Definition: odometry_plugin.cpp:104
mapviz_plugins::PointDrawingPlugin::BufferSizeChanged
virtual void BufferSizeChanged(int value)
Definition: point_drawing_plugin.cpp:245
mapviz_plugins::OdometryPlugin::Paint
void Paint(QPainter *painter, double x, double y, double scale)
Definition: odometry_plugin.cpp:250
odometry_plugin.h
mapviz::MapvizPlugin::PrintErrorHelper
static void PrintErrorHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
mapviz_plugins::PointDrawingPlugin::SetColor
virtual void SetColor(const QColor &color)
Definition: point_drawing_plugin.cpp:405
mapviz_plugins::OdometryPlugin::OdometryPlugin
OdometryPlugin()
Definition: odometry_plugin.cpp:57
geometry_util.h
ros::Subscriber::shutdown
void shutdown()
mapviz_plugins::PointDrawingPlugin::SetStaticArrowSizes
virtual void SetStaticArrowSizes(bool isChecked)
Definition: point_drawing_plugin.cpp:149
mapviz_plugins::PointDrawingPlugin::SetUseLatestTransforms
virtual void SetUseLatestTransforms(bool checked)
Definition: point_drawing_plugin.cpp:175
mapviz_plugins::PointDrawingPlugin::pushPoint
void pushPoint(StampedPoint point)
Definition: point_drawing_plugin.cpp:198
mapviz_plugins::PointDrawingPlugin::StampedPoint::source_frame
std::string source_frame
Definition: point_drawing_plugin.h:66
mapviz_plugins::OdometryPlugin::config_widget_
QWidget * config_widget_
Definition: odometry_plugin.h:95
mapviz_plugins::PointDrawingPlugin::positionTolerance
double positionTolerance() const
Definition: point_drawing_plugin.cpp:235
swri_image_util::ProjectEllipsoid
cv::Mat ProjectEllipsoid(const cv::Mat &ellipsiod)
mapviz_plugins::OdometryPlugin::SaveConfig
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
Definition: odometry_plugin.cpp:396
class_list_macros.h
mapviz_plugins::PointDrawingPlugin::LINES
@ LINES
Definition: point_drawing_plugin.h:76
tf::Point
tf::Vector3 Point
transform_util.h
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
mapviz_plugins::PointDrawingPlugin::DrawCovariance
virtual void DrawCovariance()
Definition: point_drawing_plugin.cpp:634
mapviz_plugins::OdometryPlugin::ui_
Ui::odometry_config ui_
Definition: odometry_plugin.h:94
mapviz_plugins::PointDrawingPlugin::PositionToleranceChanged
virtual void PositionToleranceChanged(double value)
Definition: point_drawing_plugin.cpp:155
mapviz::MapvizPlugin::PrintWarningHelper
static void PrintWarningHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
mapviz_plugins::PointDrawingPlugin::bufferSize
double bufferSize() const
Definition: point_drawing_plugin.cpp:223
mapviz_plugins::OdometryPlugin::LoadConfig
void LoadConfig(const YAML::Node &node, const std::string &path)
Definition: odometry_plugin.cpp:286
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
mapviz_plugins::OdometryPlugin::has_message_
bool has_message_
Definition: odometry_plugin.h:98
mapviz_plugins::PointDrawingPlugin::POINTS
@ POINTS
Definition: point_drawing_plugin.h:77
mapviz_plugins::OdometryPlugin::odometry_sub_
ros::Subscriber odometry_sub_
Definition: odometry_plugin.h:97
mapviz::MapvizPlugin::PrintInfoHelper
static void PrintInfoHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
mapviz::MapvizPlugin::canvas_
QGLWidget * canvas_
mapviz_plugins::PointDrawingPlugin::StampedPoint::orientation
tf::Quaternion orientation
Definition: point_drawing_plugin.h:61
mapviz_plugins::PointDrawingPlugin::ShowAllCovariancesToggled
virtual void ShowAllCovariancesToggled(bool checked)
Definition: point_drawing_plugin.cpp:170
mapviz_plugins::PointDrawingPlugin::StampedPoint::transformed_cov_points
std::vector< tf::Point > transformed_cov_points
Definition: point_drawing_plugin.h:71
mapviz_plugins::OdometryPlugin::Draw
void Draw(double x, double y, double scale)
Definition: odometry_plugin.cpp:237
mapviz_plugins::PointDrawingPlugin::ARROWS
@ ARROWS
Definition: point_drawing_plugin.h:78
mapviz_plugins::PointDrawingPlugin::SetArrowSize
virtual void SetArrowSize(int arrowSize)
Definition: point_drawing_plugin.cpp:119
mapviz_plugins::PointDrawingPlugin::SetDrawStyle
virtual void SetDrawStyle(QString style)
Definition: point_drawing_plugin.cpp:125
mapviz_plugins::OdometryPlugin
Definition: odometry_plugin.h:57
mapviz_plugins::OdometryPlugin::TopicEdited
void TopicEdited()
Definition: odometry_plugin.cpp:116
ROS_ERROR
#define ROS_ERROR(...)
mapviz_plugins::PointDrawingPlugin::StampedPoint::stamp
ros::Time stamp
Definition: point_drawing_plugin.h:68
mapviz_plugins::PointDrawingPlugin::StampedPoint::cov_points
std::vector< tf::Point > cov_points
Definition: point_drawing_plugin.h:70
mapviz::MapvizPlugin
mapviz_plugins::OdometryPlugin::PrintInfo
void PrintInfo(const std::string &message)
Definition: odometry_plugin.cpp:212
mapviz_plugins::OdometryPlugin::PrintError
void PrintError(const std::string &message)
Definition: odometry_plugin.cpp:207
tf
mapviz::MapvizPlugin::initialized_
bool initialized_
mapviz_plugins::OdometryPlugin::Initialize
bool Initialize(QGLWidget *canvas)
Definition: odometry_plugin.cpp:229
mapviz_plugins::PointDrawingPlugin::single_frame_
bool single_frame_
Definition: point_drawing_plugin.h:123
mapviz_plugins::OdometryPlugin::~OdometryPlugin
virtual ~OdometryPlugin()
Definition: odometry_plugin.cpp:100
ROS_INFO
#define ROS_INFO(...)
ros::master::TopicInfo
mapviz_plugins::PointDrawingPlugin::StampedPoint::point
tf::Point point
Definition: point_drawing_plugin.h:60
swri_transform_util::GetUpperLeft
tf::Matrix3x3 GetUpperLeft(const boost::array< double, 36 > &matrix)
mapviz_plugins
Definition: attitude_indicator_plugin.h:61
master.h
mapviz::MapvizPlugin::node_
ros::NodeHandle node_
mapviz_plugins::OdometryPlugin::odometryCallback
void odometryCallback(const nav_msgs::OdometryConstPtr odometry)
Definition: odometry_plugin.cpp:139
tf::Quaternion
mapviz::SelectTopicDialog::selectTopic
static ros::master::TopicInfo selectTopic(const std::string &datatype, QWidget *parent=0)
ros::master::TopicInfo::name
std::string name
mapviz_plugins::PointDrawingPlugin::points
const std::deque< StampedPoint > & points() const
Definition: point_drawing_plugin.cpp:240


mapviz_plugins
Author(s): Marc Alban
autogenerated on Sun Sep 8 2024 02:27:14