marker_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 <cmath>
34 #include <cstdio>
35 #include <vector>
36 
37 // Boost libraries
38 #include <boost/algorithm/string.hpp>
39 
40 // QT libraries
41 #include <QDialog>
42 #include <QGLWidget>
43 
44 // ROS libraries
45 #include <ros/master.h>
46 
48 
50 
51 // Declare plugin
54 
55 namespace mapviz_plugins
56 {
57 #define IS_INSTANCE(msg, type) \
58  (msg->getDataType() == ros::message_traits::datatype<type>())
59 
60  MarkerPlugin::MarkerPlugin() :
61  config_widget_(new QWidget()),
62  connected_(false)
63  {
64  ui_.setupUi(config_widget_);
65 
66  // Set background white
67  QPalette p(config_widget_->palette());
68  p.setColor(QPalette::Background, Qt::white);
69  config_widget_->setPalette(p);
70 
71  // Set status text red
72  QPalette p3(ui_.status->palette());
73  p3.setColor(QPalette::Text, Qt::red);
74  ui_.status->setPalette(p3);
75 
76  QObject::connect(ui_.selecttopic, SIGNAL(clicked()), this, SLOT(SelectTopic()));
77  QObject::connect(ui_.topic, SIGNAL(editingFinished()), this, SLOT(TopicEdited()));
78 
79  startTimer(1000);
80  }
81 
83  {
84  }
85 
87  {
88  markers_.clear();
89  }
90 
92  {
94  "visualization_msgs/Marker",
95  "visualization_msgs/MarkerArray");
96 
97  if (topic.name.empty())
98  {
99  return;
100  }
101 
102  ui_.topic->setText(QString::fromStdString(topic.name));
103  TopicEdited();
104  }
105 
107  {
108  std::string topic = ui_.topic->text().trimmed().toStdString();
109  if (topic != topic_)
110  {
111  initialized_ = false;
112  markers_.clear();
113  has_message_ = false;
114  PrintWarning("No messages received.");
115 
117  connected_ = false;
118 
119  topic_ = topic;
120  if (!topic.empty())
121  {
123  topic_, 100, &MarkerPlugin::handleMessage, this);
124 
125  ROS_INFO("Subscribing to %s", topic_.c_str());
126  }
127  }
128  }
129 
131  {
132  connected_ = true;
133  if (IS_INSTANCE(msg, visualization_msgs::Marker))
134  {
135  handleMarker(*(msg->instantiate<visualization_msgs::Marker>()));
136  }
137  else if (IS_INSTANCE(msg, visualization_msgs::MarkerArray))
138  {
139  handleMarkerArray(*(msg->instantiate<visualization_msgs::MarkerArray>()));
140  }
141  else
142  {
143  PrintError("Unknown message type: " + msg->getDataType());
144  }
145  }
146 
147  void MarkerPlugin::handleMarker(const visualization_msgs::Marker &marker)
148  {
149  if (marker.type == visualization_msgs::Marker::ARROW &&
150  marker.points.size() == 1)
151  {
152  // Arrow markers must have either 0 or >1 points; exactly one point is
153  // invalid. If we get one with 1 point, assume it's corrupt and ignore it.
154  return;
155  }
156  if (!has_message_)
157  {
158  initialized_ = true;
159  has_message_ = true;
160  }
161 
162  // Note that unlike some plugins, this one does not store nor rely on the
163  // source_frame_ member variable. This one can potentially store many
164  // messages with different source frames, so we need to store and transform
165  // them individually.
166 
167  if (marker.action == visualization_msgs::Marker::ADD)
168  {
169  MarkerData& markerData = markers_[marker.ns][marker.id];
170  markerData.stamp = marker.header.stamp;
171  markerData.display_type = marker.type;
172  markerData.color = QColor::fromRgbF(marker.color.r, marker.color.g, marker.color.b, marker.color.a);
173  markerData.scale_x = static_cast<float>(marker.scale.x);
174  markerData.scale_y = static_cast<float>(marker.scale.y);
175  markerData.scale_z = static_cast<float>(marker.scale.z);
176  markerData.transformed = true;
177  markerData.source_frame = marker.header.frame_id;
178 
179 
180  // Since orientation was not implemented, many markers publish
181  // invalid all-zero orientations, so we need to check for this
182  // and provide a default identity transform.
183  tf::Quaternion orientation(0.0, 0.0, 0.0, 1.0);
184  if (marker.pose.orientation.x ||
185  marker.pose.orientation.y ||
186  marker.pose.orientation.z ||
187  marker.pose.orientation.w)
188  {
189  orientation = tf::Quaternion(marker.pose.orientation.x,
190  marker.pose.orientation.y,
191  marker.pose.orientation.z,
192  marker.pose.orientation.w);
193  }
194 
197  orientation,
198  tf::Vector3(marker.pose.position.x,
199  marker.pose.position.y,
200  marker.pose.position.z)));
201 
202  markerData.points.clear();
203  markerData.text = std::string();
204 
206  if (!GetTransform(markerData.source_frame, marker.header.stamp, transform))
207  {
208  markerData.transformed = false;
209  PrintError("No transform between " + markerData.source_frame + " and " + target_frame_);
210  }
211 
212  // Handle lifetime parameter
213  ros::Duration lifetime = marker.lifetime;
214  if (lifetime.isZero())
215  {
216  markerData.expire_time = ros::TIME_MAX;
217  }
218  else
219  {
220  // Temporarily add 5 seconds to fix some existing markers.
221  markerData.expire_time = ros::Time::now() + lifetime + ros::Duration(5);
222  }
223 
224  if (markerData.display_type == visualization_msgs::Marker::ARROW)
225  {
226  StampedPoint point;
227  point.color = markerData.color;
228  point.orientation = orientation;
229 
230  if (marker.points.empty())
231  {
232  // If the "points" array is empty, we'll use the pose as the base of
233  // the arrow and scale its size based on the scale_x value.
234  point.point = markerData.local_transform * tf::Point(0.0, 0.0, 0.0);
235  point.arrow_point = markerData.local_transform * tf::Point(1.0, 0.0, 0.0);
236  }
237  else
238  {
239  // Otherwise the "points" array should have exactly two values, the
240  // start and end of the arrow.
241  point.point = markerData.local_transform * tf::Point(marker.points[0].x, marker.points[0].y, marker.points[0].z);
242  point.arrow_point = markerData.local_transform * tf::Point(marker.points[1].x, marker.points[1].y, marker.points[1].z);
243  }
244 
245  markerData.points.push_back(point);
246 
247  if (!marker.points.empty())
248  {
249  // The point we just pushed back has both the start and end of the
250  // arrow, so the point we're pushing here is useless; we use it later
251  // only to indicate whether the original message had two points or not.
252  markerData.points.push_back(StampedPoint());
253  }
254 
255  transformArrow(markerData, transform);
256  }
257  else if (markerData.display_type == visualization_msgs::Marker::CYLINDER ||
258  markerData.display_type == visualization_msgs::Marker::SPHERE ||
259  markerData.display_type == visualization_msgs::Marker::SPHERE_LIST)
260  {
261  StampedPoint point;
262  point.color = markerData.color;
263  if (markerData.display_type == visualization_msgs::Marker::CYLINDER ||
264  markerData.display_type == visualization_msgs::Marker::SPHERE)
265  {
266  point.point = tf::Point(0.0, 0.0, 0.0);
267  point.transformed_point = transform * (markerData.local_transform * point.point);
268  markerData.points.push_back(point);
269  }
270  else
271  {
272  Q_FOREACH (const geometry_msgs::Point& markerPoint, marker.points)
273  {
274  point.point = tf::Point(markerPoint.x, markerPoint.y, markerPoint.z);
275  point.transformed_point = transform * (markerData.local_transform * point.point);
276  markerData.points.push_back(point);
277  }
278  }
279  }
280  else if (markerData.display_type == visualization_msgs::Marker::CUBE)
281  {
282  StampedPoint point;
283  point.color = markerData.color;
284 
285  point.point = tf::Point(marker.scale.x / 2, marker.scale.y / 2, 0.0);
286  point.transformed_point = transform * (markerData.local_transform * point.point);
287  markerData.points.push_back(point);
288 
289  point.point = tf::Point(-marker.scale.x / 2, marker.scale.y / 2, 0.0);
290  point.transformed_point = transform * (markerData.local_transform * point.point);
291  markerData.points.push_back(point);
292 
293  point.point = tf::Point(-marker.scale.x / 2, -marker.scale.y / 2, 0.0);
294  point.transformed_point = transform * (markerData.local_transform * point.point);
295  markerData.points.push_back(point);
296 
297  point.point = tf::Point(marker.scale.x / 2, -marker.scale.y / 2, 0.0);
298  point.transformed_point = transform * (markerData.local_transform * point.point);
299  markerData.points.push_back(point);
300  }
301  else if (markerData.display_type == visualization_msgs::Marker::TEXT_VIEW_FACING)
302  {
303  StampedPoint point;
304  point.point = tf::Point(0.0, 0.0, 0.0);
305  point.transformed_point = transform * (markerData.local_transform * point.point);
306  point.color = markerData.color;
307 
308  markerData.points.push_back(point);
309  markerData.text = marker.text;
310  }
311  else
312  {
313  for (unsigned int i = 0; i < marker.points.size(); i++)
314  {
315  StampedPoint point;
316  point.point = tf::Point(marker.points[i].x, marker.points[i].y, marker.points[i].z);
317  point.transformed_point = transform * (markerData.local_transform * point.point);
318 
319  if (i < marker.colors.size())
320  {
321  point.color = QColor::fromRgbF(
322  marker.colors[i].r,
323  marker.colors[i].g,
324  marker.colors[i].b,
325  marker.colors[i].a);
326  }
327  else
328  {
329  point.color = markerData.color;
330  }
331 
332  markerData.points.push_back(point);
333  }
334  }
335  }
336  else
337  {
338  markers_[marker.ns].erase(marker.id);
339  }
340  }
341 
350  const swri_transform_util::Transform& transform)
351  {
352  // The first point in the markerData.points array always represents the
353  // base of the arrow.
354  StampedPoint& point = markerData.points.front();
355  tf::Point arrowOffset;
356  if (markerData.points.size() == 1)
357  {
358  // If the markerData only has a single point, that means its "point" is
359  // the base of the arrow and the arrow's angle and length are determined
360  // by the orientation and scale_x.
361  point.transformed_point = transform * (markerData.local_transform * point.point);
362  tf::Transform arrow_tf(tf::Transform(
363  transform.GetOrientation()) * point.orientation,
364  tf::Point(0.0, 0.0, 0.0));
366  arrow_tf * point.arrow_point * markerData.scale_x;
367  arrowOffset = tf::Point(0.25, 0.0, 0.0);
368  }
369  else
370  {
371  // If the markerData has two points, that means that the start and end points
372  // of the arrow were explicitly specified in the original message, so the
373  // length and angle are determined by them.
374  point.transformed_point = transform * point.point;
375  point.transformed_arrow_point = transform * point.arrow_point;
376  // Also, in this mode, scale_y is the diameter of the arrow's head.
377  arrowOffset = tf::Point(0.25 * markerData.scale_y, 0.0, 0.0);
378  }
379 
380  tf::Vector3 pointDiff = point.transformed_arrow_point - point.transformed_point;
381  double angle = std::atan2(pointDiff.getY(), pointDiff.getX());
382 
383  tf::Transform left_tf(tf::createQuaternionFromRPY(0, 0, M_PI*0.75 + angle));
384  tf::Transform right_tf(tf::createQuaternionFromRPY(0, 0, -M_PI*0.75 + angle));
385 
386  point.transformed_arrow_left = point.transformed_arrow_point + left_tf * arrowOffset;
387  point.transformed_arrow_right = point.transformed_arrow_point + right_tf * arrowOffset;
388  }
389 
390  void MarkerPlugin::handleMarkerArray(const visualization_msgs::MarkerArray &markers)
391  {
392  for (unsigned int i = 0; i < markers.markers.size(); i++)
393  {
394  handleMarker(markers.markers[i]);
395  }
396  }
397 
398  void MarkerPlugin::PrintError(const std::string& message)
399  {
400  PrintErrorHelper(ui_.status, message);
401  }
402 
403  void MarkerPlugin::PrintInfo(const std::string& message)
404  {
405  PrintInfoHelper(ui_.status, message);
406  }
407 
408  void MarkerPlugin::PrintWarning(const std::string& message)
409  {
410  PrintWarningHelper(ui_.status, message);
411  }
412 
413  QWidget* MarkerPlugin::GetConfigWidget(QWidget* parent)
414  {
415  config_widget_->setParent(parent);
416 
417  return config_widget_;
418  }
419 
420  bool MarkerPlugin::Initialize(QGLWidget* canvas)
421  {
422  canvas_ = canvas;
423 
424  return true;
425  }
426 
427  void MarkerPlugin::Draw(double x, double y, double scale)
428  {
429  ros::Time now = ros::Time::now();
430 
431  std::map<std::string, std::map<int, MarkerData> >::iterator nsIter;
432  for (nsIter = markers_.begin(); nsIter != markers_.end(); ++nsIter)
433  {
434  std::map<int, MarkerData>::iterator markerIter;
435  for (markerIter = nsIter->second.begin(); markerIter != nsIter->second.end();)
436  {
437  MarkerData& marker = markerIter->second;
438 
439  if (marker.expire_time > now)
440  {
441  if (marker.transformed)
442  {
443  glColor4d(marker.color.redF(), marker.color.greenF(), marker.color.blueF(), marker.color.alphaF());
444 
445  if (marker.display_type == visualization_msgs::Marker::ARROW)
446  {
447  if (marker.points.size() == 1)
448  {
449  // If the marker only has one point, use scale_y as the arrow width.
450  glLineWidth(marker.scale_y);
451  }
452  else
453  {
454  // If the marker has both start and end points explicitly specified, use
455  // scale_x as the shaft diameter.
456  glLineWidth(marker.scale_x);
457  }
458  glBegin(GL_LINES);
459 
460  std::list<StampedPoint>::iterator point_it = marker.points.begin();
461  for (; point_it != marker.points.end(); ++point_it)
462  {
463  glColor4d(
464  point_it->color.redF(),
465  point_it->color.greenF(),
466  point_it->color.blueF(),
467  point_it->color.alphaF());
468 
469  glVertex2d(
470  point_it->transformed_point.getX(),
471  point_it->transformed_point.getY());
472  glVertex2d(
473  point_it->transformed_arrow_point.getX(),
474  point_it->transformed_arrow_point.getY());
475  glVertex2d(
476  point_it->transformed_arrow_point.getX(),
477  point_it->transformed_arrow_point.getY());
478  glVertex2d(
479  point_it->transformed_arrow_left.getX(),
480  point_it->transformed_arrow_left.getY());
481  glVertex2d(
482  point_it->transformed_arrow_point.getX(),
483  point_it->transformed_arrow_point.getY());
484  glVertex2d(
485  point_it->transformed_arrow_right.getX(),
486  point_it->transformed_arrow_right.getY());
487  }
488 
489  glEnd();
490  }
491  else if (marker.display_type == visualization_msgs::Marker::LINE_STRIP)
492  {
493  glLineWidth(marker.scale_x);
494  glBegin(GL_LINE_STRIP);
495 
496  std::list<StampedPoint>::iterator point_it = marker.points.begin();
497  for (; point_it != marker.points.end(); ++point_it)
498  {
499  glColor4d(
500  point_it->color.redF(),
501  point_it->color.greenF(),
502  point_it->color.blueF(),
503  point_it->color.alphaF());
504 
505  glVertex2d(
506  point_it->transformed_point.getX(),
507  point_it->transformed_point.getY());
508  }
509 
510  glEnd();
511  }
512  else if (marker.display_type == visualization_msgs::Marker::LINE_LIST)
513  {
514  glLineWidth(marker.scale_x);
515  glBegin(GL_LINES);
516 
517  std::list<StampedPoint>::iterator point_it = marker.points.begin();
518  for (; point_it != marker.points.end(); ++point_it)
519  {
520  glColor4d(
521  point_it->color.redF(),
522  point_it->color.greenF(),
523  point_it->color.blueF(),
524  point_it->color.alphaF());
525 
526  glVertex2d(
527  point_it->transformed_point.getX(),
528  point_it->transformed_point.getY());
529  }
530 
531  glEnd();
532  }
533  else if (marker.display_type == visualization_msgs::Marker::POINTS)
534  {
535  glPointSize(marker.scale_x);
536  glBegin(GL_POINTS);
537 
538  std::list<StampedPoint>::iterator point_it = marker.points.begin();
539  for (; point_it != marker.points.end(); ++point_it)
540  {
541  glColor4d(
542  point_it->color.redF(),
543  point_it->color.greenF(),
544  point_it->color.blueF(),
545  point_it->color.alphaF());
546 
547  glVertex2d(
548  point_it->transformed_point.getX(),
549  point_it->transformed_point.getY());
550  }
551 
552  glEnd();
553  }
554  else if (marker.display_type == visualization_msgs::Marker::TRIANGLE_LIST)
555  {
556  glBegin(GL_TRIANGLES);
557 
558  std::list<StampedPoint>::iterator point_it = marker.points.begin();
559  for (; point_it != marker.points.end(); ++point_it)
560  {
561  glColor4d(
562  point_it->color.redF(),
563  point_it->color.greenF(),
564  point_it->color.blueF(),
565  point_it->color.alphaF());
566 
567  glVertex2d(
568  point_it->transformed_point.getX(),
569  point_it->transformed_point.getY());
570  }
571 
572  glEnd();
573  }
574  else if (marker.display_type == visualization_msgs::Marker::CYLINDER ||
575  marker.display_type == visualization_msgs::Marker::SPHERE ||
576  marker.display_type == visualization_msgs::Marker::SPHERE_LIST)
577  {
578  std::list<StampedPoint>::iterator point_it = marker.points.begin();
579  for (; point_it != marker.points.end(); ++point_it)
580  {
581  glColor4d(
582  point_it->color.redF(),
583  point_it->color.greenF(),
584  point_it->color.blueF(),
585  point_it->color.alphaF());
586 
587 
588  glBegin(GL_TRIANGLE_FAN);
589 
590 
591  double marker_x = point_it->transformed_point.getX();
592  double marker_y = point_it->transformed_point.getY();
593 
594  glVertex2d(marker_x, marker_y);
595 
596  for (int32_t i = 0; i <= 360; i += 10)
597  {
598  double radians = static_cast<double>(i) * static_cast<double>(swri_math_util::_deg_2_rad);
599  // Spheres may be specified w/ only one scale value
600  if(marker.scale_y == 0.0)
601  {
602  marker.scale_y = marker.scale_x;
603  }
604  glVertex2d(
605  marker_x + std::sin(radians) * marker.scale_x,
606  marker_y + std::cos(radians) * marker.scale_y);
607  }
608 
609  glEnd();
610  }
611  }
612  else if (marker.display_type == visualization_msgs::Marker::CUBE ||
613  marker.display_type == visualization_msgs::Marker::CUBE_LIST)
614  {
615  std::list<StampedPoint>::iterator point_it = marker.points.begin();
616  glBegin(GL_TRIANGLE_FAN);
617  for (; point_it != marker.points.end(); ++point_it)
618  {
619  glColor4d(
620  point_it->color.redF(),
621  point_it->color.greenF(),
622  point_it->color.blueF(),
623  point_it->color.alphaF());
624 
625  glVertex2d(point_it->transformed_point.getX(), point_it->transformed_point.getY());
626  }
627  glEnd();
628  }
629 
630  PrintInfo("OK");
631  }
632 
633  ++markerIter;
634  }
635  else
636  {
637  PrintInfo("OK");
638  markerIter = nsIter->second.erase(markerIter);
639  }
640  }
641  }
642  }
643 
644  void MarkerPlugin::Paint(QPainter* painter, double x, double y, double scale)
645  {
646  // Most of the marker drawing is done using OpenGL commands, but text labels
647  // are rendered using a QPainter. This is intended primarily as an example
648  // of how the QPainter works.
649  ros::Time now = ros::Time::now();
650 
651  // We don't want the text to be rotated or scaled, but we do want it to be
652  // translated appropriately. So, we save off the current world transform
653  // and reset it; when we actually draw the text, we'll manually translate
654  // it to the right place.
655  QTransform tf = painter->worldTransform();
656  QFont font("Helvetica", 10);
657  painter->setFont(font);
658  painter->save();
659  painter->resetTransform();
660 
661  std::map<std::string, std::map<int, MarkerData> >::iterator nsIter;
662  for (nsIter = markers_.begin(); nsIter != markers_.end(); ++nsIter)
663  {
664  std::map<int, MarkerData>::iterator markerIter;
665  for (markerIter = nsIter->second.begin(); markerIter != nsIter->second.end(); ++markerIter)
666  {
667  MarkerData& marker = markerIter->second;
668 
669  if (marker.display_type != visualization_msgs::Marker::TEXT_VIEW_FACING ||
670  marker.expire_time <= now ||
671  !marker.transformed)
672  {
673  continue;
674  }
675 
676  QPen pen(QBrush(QColor(marker.color.red(), marker.color.green(),
677  marker.color.blue())), 1);
678  painter->setPen(pen);
679 
680  StampedPoint& rosPoint = marker.points.front();
681  QPointF point = tf.map(QPointF(rosPoint.transformed_point.x(),
682  rosPoint.transformed_point.y()));
683 
684  // Get bounding rectangle
685  QRectF rect(point, QSizeF(10,10));
686  rect = painter->boundingRect(rect, Qt::AlignLeft ,QString(marker.text.c_str()));
687  painter->drawText(rect, QString(marker.text.c_str()));
688 
689  PrintInfo("OK");
690  }
691  }
692 
693  painter->restore();
694  }
695 
697  {
698  std::map<std::string, std::map<int, MarkerData> >::iterator nsIter;
699  for (nsIter = markers_.begin(); nsIter != markers_.end(); ++nsIter)
700  {
701  std::map<int, MarkerData>::iterator markerIter;
702  for (markerIter = nsIter->second.begin(); markerIter != nsIter->second.end(); ++markerIter)
703  {
704  MarkerData& marker = markerIter->second;
705 
707  if (GetTransform(marker.source_frame, marker.stamp, transform))
708  {
709  marker.transformed = true;
710 
711  if (marker.display_type == visualization_msgs::Marker::ARROW)
712  {
713  // Points for the ARROW marker type are stored a bit differently
714  // than other types, so they have their own special transform case.
715  transformArrow(marker, transform);
716  }
717  else
718  {
719  std::list<StampedPoint>::iterator point_it;
720  for (point_it = marker.points.begin(); point_it != marker.points.end(); ++point_it)
721  {
722  point_it->transformed_point = transform * (marker.local_transform * point_it->point);
723  }
724  }
725  }
726  else
727  {
728  marker.transformed = false;
729  }
730  }
731  }
732  }
733 
734  void MarkerPlugin::LoadConfig(const YAML::Node& node, const std::string& path)
735  {
736  if (node["topic"])
737  {
738  std::string topic;
739  node["topic"] >> topic;
740  ui_.topic->setText(boost::trim_copy(topic).c_str());
741 
742  TopicEdited();
743  }
744  }
745 
746  void MarkerPlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path)
747  {
748  emitter << YAML::Key << "topic" << YAML::Value << boost::trim_copy(ui_.topic->text().toStdString());
749  }
750 
751  void MarkerPlugin::timerEvent(QTimerEvent *event)
752  {
753  bool new_connected = (marker_sub_.getNumPublishers() > 0);
754  if (connected_ && !new_connected)
755  {
757  if (!topic_.empty())
758  {
760  topic_, 100, &MarkerPlugin::handleMessage, this);
761  }
762  }
763  connected_ = new_connected;
764  }
765 }
766 
bool GetTransform(const ros::Time &stamp, swri_transform_util::Transform &transform, bool use_latest_transforms=true)
static ros::master::TopicInfo selectTopic(const std::string &datatype, QWidget *parent=0)
static tf::Quaternion createQuaternionFromRPY(double roll, double pitch, double yaw)
static const long double _deg_2_rad
ros::NodeHandle node_
void transform(Route &route, const swri_transform_util::Transform &transform, const std::string &target_frame)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void handleMessage(const topic_tools::ShapeShifter::ConstPtr &msg)
void handleMarker(const visualization_msgs::Marker &marker)
void Draw(double x, double y, double scale)
std::map< std::string, std::map< int, MarkerData > > markers_
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)
tf::Quaternion GetOrientation() const
TFSIMD_FORCE_INLINE const tfScalar & getY() const
std::string target_frame_
tf::Vector3 Point
void PrintError(const std::string &message)
static void PrintInfoHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
QWidget * GetConfigWidget(QWidget *parent)
void transformArrow(MarkerData &markerData, const swri_transform_util::Transform &transform)
void LoadConfig(const YAML::Node &node, const std::string &path)
#define IS_INSTANCE(msg, type)
TFSIMD_FORCE_INLINE const tfScalar & x() const
void PrintWarning(const std::string &message)
#define ROS_INFO(...)
uint32_t getNumPublishers() const
TFSIMD_FORCE_INLINE const tfScalar & y() const
ROSTIME_DECL const Time TIME_MAX
void timerEvent(QTimerEvent *)
void Paint(QPainter *painter, double x, double y, double scale)
swri_transform_util::Transform local_transform
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
TFSIMD_FORCE_INLINE const tfScalar & getX() const
static Time now()
void handleMarkerArray(const visualization_msgs::MarkerArray &markers)
void PrintInfo(const std::string &message)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
bool Initialize(QGLWidget *canvas)


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