38 #include <boost/algorithm/string.hpp> 57 #define IS_INSTANCE(msg, type) \ 58 (msg->getDataType() == ros::message_traits::datatype<type>()) 60 MarkerPlugin::MarkerPlugin() :
61 config_widget_(new QWidget()),
68 p.setColor(QPalette::Background, Qt::white);
72 QPalette p3(
ui_.status->palette());
73 p3.setColor(QPalette::Text, Qt::red);
74 ui_.status->setPalette(p3);
76 QObject::connect(
ui_.selecttopic, SIGNAL(clicked()),
this, SLOT(
SelectTopic()));
77 QObject::connect(
ui_.topic, SIGNAL(editingFinished()),
this, SLOT(
TopicEdited()));
94 "visualization_msgs/Marker",
95 "visualization_msgs/MarkerArray");
97 if (topic.
name.empty())
102 ui_.topic->setText(QString::fromStdString(topic.
name));
108 std::string topic =
ui_.topic->text().trimmed().toStdString();
125 ROS_INFO(
"Subscribing to %s", topic_.c_str());
135 handleMarker(*(msg->instantiate<visualization_msgs::Marker>()));
137 else if (
IS_INSTANCE(msg, visualization_msgs::MarkerArray))
143 PrintError(
"Unknown message type: " + msg->getDataType());
149 if (marker.type == visualization_msgs::Marker::ARROW &&
150 marker.points.size() == 1)
167 if (marker.action == visualization_msgs::Marker::ADD)
170 markerData.
stamp = marker.header.stamp;
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);
184 if (marker.pose.orientation.x ||
185 marker.pose.orientation.y ||
186 marker.pose.orientation.z ||
187 marker.pose.orientation.w)
190 marker.pose.orientation.y,
191 marker.pose.orientation.z,
192 marker.pose.orientation.w);
199 marker.pose.position.y,
200 marker.pose.position.z)));
202 markerData.
points.clear();
203 markerData.
text = std::string();
224 if (markerData.
display_type == visualization_msgs::Marker::ARROW)
230 if (marker.points.empty())
245 markerData.
points.push_back(point);
247 if (!marker.points.empty())
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)
263 if (markerData.
display_type == visualization_msgs::Marker::CYLINDER ||
264 markerData.
display_type == visualization_msgs::Marker::SPHERE)
268 markerData.
points.push_back(point);
272 Q_FOREACH (
const geometry_msgs::Point& markerPoint, marker.points)
274 point.
point =
tf::Point(markerPoint.x, markerPoint.y, markerPoint.z);
276 markerData.
points.push_back(point);
280 else if (markerData.
display_type == visualization_msgs::Marker::CUBE)
285 point.
point =
tf::Point(marker.scale.x / 2, marker.scale.y / 2, 0.0);
287 markerData.
points.push_back(point);
289 point.
point =
tf::Point(-marker.scale.x / 2, marker.scale.y / 2, 0.0);
291 markerData.
points.push_back(point);
293 point.
point =
tf::Point(-marker.scale.x / 2, -marker.scale.y / 2, 0.0);
295 markerData.
points.push_back(point);
297 point.
point =
tf::Point(marker.scale.x / 2, -marker.scale.y / 2, 0.0);
299 markerData.
points.push_back(point);
301 else if (markerData.
display_type == visualization_msgs::Marker::TEXT_VIEW_FACING)
308 markerData.
points.push_back(point);
309 markerData.
text = marker.text;
313 for (
unsigned int i = 0; i < marker.points.size(); i++)
316 point.
point =
tf::Point(marker.points[i].x, marker.points[i].y, marker.points[i].z);
319 if (i < marker.colors.size())
321 point.
color = QColor::fromRgbF(
332 markerData.
points.push_back(point);
338 markers_[marker.ns].erase(marker.id);
356 if (markerData.
points.size() == 1)
381 double angle = std::atan2(pointDiff.
getY(), pointDiff.
getX());
392 for (
unsigned int i = 0; i < markers.markers.size(); i++)
431 std::map<std::string, std::map<int, MarkerData> >::iterator nsIter;
434 std::map<int, MarkerData>::iterator markerIter;
435 for (markerIter = nsIter->second.begin(); markerIter != nsIter->second.end();)
443 glColor4d(marker.
color.redF(), marker.
color.greenF(), marker.
color.blueF(), marker.
color.alphaF());
445 if (marker.
display_type == visualization_msgs::Marker::ARROW)
447 if (marker.
points.size() == 1)
460 std::list<StampedPoint>::iterator point_it = marker.
points.begin();
461 for (; point_it != marker.
points.end(); ++point_it)
464 point_it->color.redF(),
465 point_it->color.greenF(),
466 point_it->color.blueF(),
467 point_it->color.alphaF());
470 point_it->transformed_point.getX(),
471 point_it->transformed_point.getY());
473 point_it->transformed_arrow_point.getX(),
474 point_it->transformed_arrow_point.getY());
476 point_it->transformed_arrow_point.getX(),
477 point_it->transformed_arrow_point.getY());
479 point_it->transformed_arrow_left.getX(),
480 point_it->transformed_arrow_left.getY());
482 point_it->transformed_arrow_point.getX(),
483 point_it->transformed_arrow_point.getY());
485 point_it->transformed_arrow_right.getX(),
486 point_it->transformed_arrow_right.getY());
491 else if (marker.
display_type == visualization_msgs::Marker::LINE_STRIP)
494 glBegin(GL_LINE_STRIP);
496 std::list<StampedPoint>::iterator point_it = marker.
points.begin();
497 for (; point_it != marker.
points.end(); ++point_it)
500 point_it->color.redF(),
501 point_it->color.greenF(),
502 point_it->color.blueF(),
503 point_it->color.alphaF());
506 point_it->transformed_point.getX(),
507 point_it->transformed_point.getY());
512 else if (marker.
display_type == visualization_msgs::Marker::LINE_LIST)
517 std::list<StampedPoint>::iterator point_it = marker.
points.begin();
518 for (; point_it != marker.
points.end(); ++point_it)
521 point_it->color.redF(),
522 point_it->color.greenF(),
523 point_it->color.blueF(),
524 point_it->color.alphaF());
527 point_it->transformed_point.getX(),
528 point_it->transformed_point.getY());
533 else if (marker.
display_type == visualization_msgs::Marker::POINTS)
538 std::list<StampedPoint>::iterator point_it = marker.
points.begin();
539 for (; point_it != marker.
points.end(); ++point_it)
542 point_it->color.redF(),
543 point_it->color.greenF(),
544 point_it->color.blueF(),
545 point_it->color.alphaF());
548 point_it->transformed_point.getX(),
549 point_it->transformed_point.getY());
554 else if (marker.
display_type == visualization_msgs::Marker::TRIANGLE_LIST)
556 glBegin(GL_TRIANGLES);
558 std::list<StampedPoint>::iterator point_it = marker.
points.begin();
559 for (; point_it != marker.
points.end(); ++point_it)
562 point_it->color.redF(),
563 point_it->color.greenF(),
564 point_it->color.blueF(),
565 point_it->color.alphaF());
568 point_it->transformed_point.getX(),
569 point_it->transformed_point.getY());
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)
578 std::list<StampedPoint>::iterator point_it = marker.
points.begin();
579 for (; point_it != marker.
points.end(); ++point_it)
582 point_it->color.redF(),
583 point_it->color.greenF(),
584 point_it->color.blueF(),
585 point_it->color.alphaF());
588 glBegin(GL_TRIANGLE_FAN);
591 double marker_x = point_it->transformed_point.getX();
592 double marker_y = point_it->transformed_point.getY();
594 glVertex2d(marker_x, marker_y);
596 for (int32_t i = 0; i <= 360; i += 10)
605 marker_x + std::sin(radians) * marker.
scale_x,
606 marker_y + std::cos(radians) * marker.
scale_y);
612 else if (marker.
display_type == visualization_msgs::Marker::CUBE ||
613 marker.
display_type == visualization_msgs::Marker::CUBE_LIST)
615 std::list<StampedPoint>::iterator point_it = marker.
points.begin();
616 glBegin(GL_TRIANGLE_FAN);
617 for (; point_it != marker.
points.end(); ++point_it)
620 point_it->color.redF(),
621 point_it->color.greenF(),
622 point_it->color.blueF(),
623 point_it->color.alphaF());
625 glVertex2d(point_it->transformed_point.getX(), point_it->transformed_point.getY());
638 markerIter = nsIter->second.erase(markerIter);
655 QTransform
tf = painter->worldTransform();
656 QFont font(
"Helvetica", 10);
657 painter->setFont(font);
659 painter->resetTransform();
661 std::map<std::string, std::map<int, MarkerData> >::iterator nsIter;
664 std::map<int, MarkerData>::iterator markerIter;
665 for (markerIter = nsIter->second.begin(); markerIter != nsIter->second.end(); ++markerIter)
669 if (marker.
display_type != visualization_msgs::Marker::TEXT_VIEW_FACING ||
676 QPen pen(QBrush(QColor(marker.
color.red(), marker.
color.green(),
677 marker.
color.blue())), 1);
678 painter->setPen(pen);
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()));
698 std::map<std::string, std::map<int, MarkerData> >::iterator nsIter;
701 std::map<int, MarkerData>::iterator markerIter;
702 for (markerIter = nsIter->second.begin(); markerIter != nsIter->second.end(); ++markerIter)
711 if (marker.
display_type == visualization_msgs::Marker::ARROW)
719 std::list<StampedPoint>::iterator point_it;
720 for (point_it = marker.
points.begin(); point_it != marker.
points.end(); ++point_it)
722 point_it->transformed_point = transform * (marker.
local_transform * point_it->point);
739 node[
"topic"] >> topic;
740 ui_.topic->setText(boost::trim_copy(topic).c_str());
748 emitter << YAML::Key <<
"topic" << YAML::Value << boost::trim_copy(
ui_.topic->text().toStdString());
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
void transform(Route &route, const swri_transform_util::Transform &transform, const std::string &target_frame)
tf::Point transformed_arrow_right
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)
std::list< StampedPoint > points
void handleMarker(const visualization_msgs::Marker &marker)
tf::Quaternion orientation
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)
tf::Point transformed_point
ros::Subscriber marker_sub_
static void PrintErrorHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
TFSIMD_FORCE_INLINE const tfScalar & getY() const
std::string target_frame_
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
tf::Point transformed_arrow_point
void PrintWarning(const std::string &message)
tf::Point transformed_arrow_left
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
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)