00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include <mapviz_plugins/marker_plugin.h>
00031
00032
00033 #include <cmath>
00034 #include <cstdio>
00035 #include <vector>
00036
00037
00038 #include <boost/algorithm/string.hpp>
00039
00040
00041 #include <QDialog>
00042 #include <QGLWidget>
00043
00044
00045 #include <ros/master.h>
00046
00047 #include <mapviz/select_topic_dialog.h>
00048
00049 #include <swri_math_util/constants.h>
00050
00051
00052 #include <pluginlib/class_list_macros.h>
00053 PLUGINLIB_EXPORT_CLASS(mapviz_plugins::MarkerPlugin, mapviz::MapvizPlugin)
00054
00055 namespace mapviz_plugins
00056 {
00057 #define IS_INSTANCE(msg, type) \
00058 (msg->getDataType() == ros::message_traits::datatype<type>())
00059
00060 MarkerPlugin::MarkerPlugin() :
00061 config_widget_(new QWidget()),
00062 connected_(false)
00063 {
00064 ui_.setupUi(config_widget_);
00065
00066
00067 QPalette p(config_widget_->palette());
00068 p.setColor(QPalette::Background, Qt::white);
00069 config_widget_->setPalette(p);
00070
00071
00072 QPalette p3(ui_.status->palette());
00073 p3.setColor(QPalette::Text, Qt::red);
00074 ui_.status->setPalette(p3);
00075
00076 QObject::connect(ui_.selecttopic, SIGNAL(clicked()), this, SLOT(SelectTopic()));
00077 QObject::connect(ui_.topic, SIGNAL(editingFinished()), this, SLOT(TopicEdited()));
00078
00079 startTimer(1000);
00080 }
00081
00082 MarkerPlugin::~MarkerPlugin()
00083 {
00084 }
00085
00086 void MarkerPlugin::ClearHistory()
00087 {
00088 markers_.clear();
00089 }
00090
00091 void MarkerPlugin::SelectTopic()
00092 {
00093 ros::master::TopicInfo topic = mapviz::SelectTopicDialog::selectTopic(
00094 "visualization_msgs/Marker",
00095 "visualization_msgs/MarkerArray");
00096
00097 if (topic.name.empty())
00098 {
00099 return;
00100 }
00101
00102 ui_.topic->setText(QString::fromStdString(topic.name));
00103 TopicEdited();
00104 }
00105
00106 void MarkerPlugin::TopicEdited()
00107 {
00108 std::string topic = ui_.topic->text().trimmed().toStdString();
00109 if (topic != topic_)
00110 {
00111 initialized_ = false;
00112 markers_.clear();
00113 has_message_ = false;
00114 PrintWarning("No messages received.");
00115
00116 marker_sub_.shutdown();
00117 connected_ = false;
00118
00119 topic_ = topic;
00120 if (!topic.empty())
00121 {
00122 marker_sub_ = node_.subscribe<topic_tools::ShapeShifter>(
00123 topic_, 100, &MarkerPlugin::handleMessage, this);
00124
00125 ROS_INFO("Subscribing to %s", topic_.c_str());
00126 }
00127 }
00128 }
00129
00130 void MarkerPlugin::handleMessage(const topic_tools::ShapeShifter::ConstPtr& msg)
00131 {
00132 connected_ = true;
00133 if (IS_INSTANCE(msg, visualization_msgs::Marker))
00134 {
00135 handleMarker(*(msg->instantiate<visualization_msgs::Marker>()));
00136 }
00137 else if (IS_INSTANCE(msg, visualization_msgs::MarkerArray))
00138 {
00139 handleMarkerArray(*(msg->instantiate<visualization_msgs::MarkerArray>()));
00140 }
00141 else
00142 {
00143 PrintError("Unknown message type: " + msg->getDataType());
00144 }
00145 }
00146
00147 void MarkerPlugin::handleMarker(const visualization_msgs::Marker &marker)
00148 {
00149 if (marker.type == visualization_msgs::Marker::ARROW &&
00150 marker.points.size() == 1)
00151 {
00152
00153
00154 return;
00155 }
00156 if (!has_message_)
00157 {
00158 initialized_ = true;
00159 has_message_ = true;
00160 }
00161
00162
00163
00164
00165
00166
00167 if (marker.action == visualization_msgs::Marker::ADD)
00168 {
00169 MarkerData& markerData = markers_[marker.ns][marker.id];
00170 markerData.stamp = marker.header.stamp;
00171 markerData.display_type = marker.type;
00172 markerData.color = QColor::fromRgbF(marker.color.r, marker.color.g, marker.color.b, marker.color.a);
00173 markerData.scale_x = static_cast<float>(marker.scale.x);
00174 markerData.scale_y = static_cast<float>(marker.scale.y);
00175 markerData.scale_z = static_cast<float>(marker.scale.z);
00176 markerData.transformed = true;
00177 markerData.source_frame = marker.header.frame_id;
00178
00179
00180
00181
00182
00183 tf::Quaternion orientation(0.0, 0.0, 0.0, 1.0);
00184 if (marker.pose.orientation.x ||
00185 marker.pose.orientation.y ||
00186 marker.pose.orientation.z ||
00187 marker.pose.orientation.w)
00188 {
00189 orientation = tf::Quaternion(marker.pose.orientation.x,
00190 marker.pose.orientation.y,
00191 marker.pose.orientation.z,
00192 marker.pose.orientation.w);
00193 }
00194
00195 markerData.local_transform = swri_transform_util::Transform(
00196 tf::Transform(
00197 orientation,
00198 tf::Vector3(marker.pose.position.x,
00199 marker.pose.position.y,
00200 marker.pose.position.z)));
00201
00202 markerData.points.clear();
00203 markerData.text = std::string();
00204
00205 swri_transform_util::Transform transform;
00206 if (!GetTransform(markerData.source_frame, marker.header.stamp, transform))
00207 {
00208 markerData.transformed = false;
00209 PrintError("No transform between " + markerData.source_frame + " and " + target_frame_);
00210 }
00211
00212
00213 ros::Duration lifetime = marker.lifetime;
00214 if (lifetime.isZero())
00215 {
00216 markerData.expire_time = ros::TIME_MAX;
00217 }
00218 else
00219 {
00220
00221 markerData.expire_time = ros::Time::now() + lifetime + ros::Duration(5);
00222 }
00223
00224 if (markerData.display_type == visualization_msgs::Marker::ARROW)
00225 {
00226 StampedPoint point;
00227 point.color = markerData.color;
00228 point.orientation = orientation;
00229
00230 if (marker.points.empty())
00231 {
00232
00233
00234 point.point = markerData.local_transform * tf::Point(0.0, 0.0, 0.0);
00235 point.arrow_point = markerData.local_transform * tf::Point(1.0, 0.0, 0.0);
00236 }
00237 else
00238 {
00239
00240
00241 point.point = markerData.local_transform * tf::Point(marker.points[0].x, marker.points[0].y, marker.points[0].z);
00242 point.arrow_point = markerData.local_transform * tf::Point(marker.points[1].x, marker.points[1].y, marker.points[1].z);
00243 }
00244
00245 markerData.points.push_back(point);
00246
00247 if (!marker.points.empty())
00248 {
00249
00250
00251
00252 markerData.points.push_back(StampedPoint());
00253 }
00254
00255 transformArrow(markerData, transform);
00256 }
00257 else if (markerData.display_type == visualization_msgs::Marker::CYLINDER ||
00258 markerData.display_type == visualization_msgs::Marker::SPHERE ||
00259 markerData.display_type == visualization_msgs::Marker::SPHERE_LIST)
00260 {
00261 StampedPoint point;
00262 point.color = markerData.color;
00263 if (markerData.display_type == visualization_msgs::Marker::CYLINDER ||
00264 markerData.display_type == visualization_msgs::Marker::SPHERE)
00265 {
00266 point.point = tf::Point(0.0, 0.0, 0.0);
00267 point.transformed_point = transform * (markerData.local_transform * point.point);
00268 markerData.points.push_back(point);
00269 }
00270 else
00271 {
00272 Q_FOREACH (const geometry_msgs::Point& markerPoint, marker.points)
00273 {
00274 point.point = tf::Point(markerPoint.x, markerPoint.y, markerPoint.z);
00275 point.transformed_point = transform * (markerData.local_transform * point.point);
00276 markerData.points.push_back(point);
00277 }
00278 }
00279 }
00280 else if (markerData.display_type == visualization_msgs::Marker::CUBE)
00281 {
00282 StampedPoint point;
00283 point.color = markerData.color;
00284
00285 point.point = tf::Point(marker.scale.x / 2, marker.scale.y / 2, 0.0);
00286 point.transformed_point = transform * (markerData.local_transform * point.point);
00287 markerData.points.push_back(point);
00288
00289 point.point = tf::Point(-marker.scale.x / 2, marker.scale.y / 2, 0.0);
00290 point.transformed_point = transform * (markerData.local_transform * point.point);
00291 markerData.points.push_back(point);
00292
00293 point.point = tf::Point(-marker.scale.x / 2, -marker.scale.y / 2, 0.0);
00294 point.transformed_point = transform * (markerData.local_transform * point.point);
00295 markerData.points.push_back(point);
00296
00297 point.point = tf::Point(marker.scale.x / 2, -marker.scale.y / 2, 0.0);
00298 point.transformed_point = transform * (markerData.local_transform * point.point);
00299 markerData.points.push_back(point);
00300 }
00301 else if (markerData.display_type == visualization_msgs::Marker::TEXT_VIEW_FACING)
00302 {
00303 StampedPoint point;
00304 point.point = tf::Point(0.0, 0.0, 0.0);
00305 point.transformed_point = transform * (markerData.local_transform * point.point);
00306 point.color = markerData.color;
00307
00308 markerData.points.push_back(point);
00309 markerData.text = marker.text;
00310 }
00311 else
00312 {
00313 for (unsigned int i = 0; i < marker.points.size(); i++)
00314 {
00315 StampedPoint point;
00316 point.point = tf::Point(marker.points[i].x, marker.points[i].y, marker.points[i].z);
00317 point.transformed_point = transform * (markerData.local_transform * point.point);
00318
00319 if (i < marker.colors.size())
00320 {
00321 point.color = QColor::fromRgbF(
00322 marker.colors[i].r,
00323 marker.colors[i].g,
00324 marker.colors[i].b,
00325 marker.colors[i].a);
00326 }
00327 else
00328 {
00329 point.color = markerData.color;
00330 }
00331
00332 markerData.points.push_back(point);
00333 }
00334 }
00335 }
00336 else
00337 {
00338 markers_[marker.ns].erase(marker.id);
00339 }
00340 }
00341
00349 void MarkerPlugin::transformArrow(MarkerData& markerData,
00350 const swri_transform_util::Transform& transform)
00351 {
00352
00353
00354 StampedPoint& point = markerData.points.front();
00355 tf::Point arrowOffset;
00356 if (markerData.points.size() == 1)
00357 {
00358
00359
00360
00361 point.transformed_point = transform * (markerData.local_transform * point.point);
00362 tf::Transform arrow_tf(tf::Transform(
00363 transform.GetOrientation()) * point.orientation,
00364 tf::Point(0.0, 0.0, 0.0));
00365 point.transformed_arrow_point = point.transformed_point +
00366 arrow_tf * point.arrow_point * markerData.scale_x;
00367 arrowOffset = tf::Point(0.25, 0.0, 0.0);
00368 }
00369 else
00370 {
00371
00372
00373
00374 point.transformed_point = transform * point.point;
00375 point.transformed_arrow_point = transform * point.arrow_point;
00376
00377 arrowOffset = tf::Point(0.25 * markerData.scale_y, 0.0, 0.0);
00378 }
00379
00380 tf::Vector3 pointDiff = point.transformed_arrow_point - point.transformed_point;
00381 double angle = std::atan2(pointDiff.getY(), pointDiff.getX());
00382
00383 tf::Transform left_tf(tf::createQuaternionFromRPY(0, 0, M_PI*0.75 + angle));
00384 tf::Transform right_tf(tf::createQuaternionFromRPY(0, 0, -M_PI*0.75 + angle));
00385
00386 point.transformed_arrow_left = point.transformed_arrow_point + left_tf * arrowOffset;
00387 point.transformed_arrow_right = point.transformed_arrow_point + right_tf * arrowOffset;
00388 }
00389
00390 void MarkerPlugin::handleMarkerArray(const visualization_msgs::MarkerArray &markers)
00391 {
00392 for (unsigned int i = 0; i < markers.markers.size(); i++)
00393 {
00394 handleMarker(markers.markers[i]);
00395 }
00396 }
00397
00398 void MarkerPlugin::PrintError(const std::string& message)
00399 {
00400 PrintErrorHelper(ui_.status, message);
00401 }
00402
00403 void MarkerPlugin::PrintInfo(const std::string& message)
00404 {
00405 PrintInfoHelper(ui_.status, message);
00406 }
00407
00408 void MarkerPlugin::PrintWarning(const std::string& message)
00409 {
00410 PrintWarningHelper(ui_.status, message);
00411 }
00412
00413 QWidget* MarkerPlugin::GetConfigWidget(QWidget* parent)
00414 {
00415 config_widget_->setParent(parent);
00416
00417 return config_widget_;
00418 }
00419
00420 bool MarkerPlugin::Initialize(QGLWidget* canvas)
00421 {
00422 canvas_ = canvas;
00423
00424 return true;
00425 }
00426
00427 void MarkerPlugin::Draw(double x, double y, double scale)
00428 {
00429 ros::Time now = ros::Time::now();
00430
00431 std::map<std::string, std::map<int, MarkerData> >::iterator nsIter;
00432 for (nsIter = markers_.begin(); nsIter != markers_.end(); ++nsIter)
00433 {
00434 std::map<int, MarkerData>::iterator markerIter;
00435 for (markerIter = nsIter->second.begin(); markerIter != nsIter->second.end();)
00436 {
00437 MarkerData& marker = markerIter->second;
00438
00439 if (marker.expire_time > now)
00440 {
00441 if (marker.transformed)
00442 {
00443 glColor4d(marker.color.redF(), marker.color.greenF(), marker.color.blueF(), marker.color.alphaF());
00444
00445 if (marker.display_type == visualization_msgs::Marker::ARROW)
00446 {
00447 if (marker.points.size() == 1)
00448 {
00449
00450 glLineWidth(marker.scale_y);
00451 }
00452 else
00453 {
00454
00455
00456 glLineWidth(marker.scale_x);
00457 }
00458 glBegin(GL_LINES);
00459
00460 std::list<StampedPoint>::iterator point_it = marker.points.begin();
00461 for (; point_it != marker.points.end(); ++point_it)
00462 {
00463 glColor4d(
00464 point_it->color.redF(),
00465 point_it->color.greenF(),
00466 point_it->color.blueF(),
00467 point_it->color.alphaF());
00468
00469 glVertex2d(
00470 point_it->transformed_point.getX(),
00471 point_it->transformed_point.getY());
00472 glVertex2d(
00473 point_it->transformed_arrow_point.getX(),
00474 point_it->transformed_arrow_point.getY());
00475 glVertex2d(
00476 point_it->transformed_arrow_point.getX(),
00477 point_it->transformed_arrow_point.getY());
00478 glVertex2d(
00479 point_it->transformed_arrow_left.getX(),
00480 point_it->transformed_arrow_left.getY());
00481 glVertex2d(
00482 point_it->transformed_arrow_point.getX(),
00483 point_it->transformed_arrow_point.getY());
00484 glVertex2d(
00485 point_it->transformed_arrow_right.getX(),
00486 point_it->transformed_arrow_right.getY());
00487 }
00488
00489 glEnd();
00490 }
00491 else if (marker.display_type == visualization_msgs::Marker::LINE_STRIP)
00492 {
00493 glLineWidth(marker.scale_x);
00494 glBegin(GL_LINE_STRIP);
00495
00496 std::list<StampedPoint>::iterator point_it = marker.points.begin();
00497 for (; point_it != marker.points.end(); ++point_it)
00498 {
00499 glColor4d(
00500 point_it->color.redF(),
00501 point_it->color.greenF(),
00502 point_it->color.blueF(),
00503 point_it->color.alphaF());
00504
00505 glVertex2d(
00506 point_it->transformed_point.getX(),
00507 point_it->transformed_point.getY());
00508 }
00509
00510 glEnd();
00511 }
00512 else if (marker.display_type == visualization_msgs::Marker::LINE_LIST)
00513 {
00514 glLineWidth(marker.scale_x);
00515 glBegin(GL_LINES);
00516
00517 std::list<StampedPoint>::iterator point_it = marker.points.begin();
00518 for (; point_it != marker.points.end(); ++point_it)
00519 {
00520 glColor4d(
00521 point_it->color.redF(),
00522 point_it->color.greenF(),
00523 point_it->color.blueF(),
00524 point_it->color.alphaF());
00525
00526 glVertex2d(
00527 point_it->transformed_point.getX(),
00528 point_it->transformed_point.getY());
00529 }
00530
00531 glEnd();
00532 }
00533 else if (marker.display_type == visualization_msgs::Marker::POINTS)
00534 {
00535 glPointSize(marker.scale_x);
00536 glBegin(GL_POINTS);
00537
00538 std::list<StampedPoint>::iterator point_it = marker.points.begin();
00539 for (; point_it != marker.points.end(); ++point_it)
00540 {
00541 glColor4d(
00542 point_it->color.redF(),
00543 point_it->color.greenF(),
00544 point_it->color.blueF(),
00545 point_it->color.alphaF());
00546
00547 glVertex2d(
00548 point_it->transformed_point.getX(),
00549 point_it->transformed_point.getY());
00550 }
00551
00552 glEnd();
00553 }
00554 else if (marker.display_type == visualization_msgs::Marker::TRIANGLE_LIST)
00555 {
00556 glBegin(GL_TRIANGLES);
00557
00558 std::list<StampedPoint>::iterator point_it = marker.points.begin();
00559 for (; point_it != marker.points.end(); ++point_it)
00560 {
00561 glColor4d(
00562 point_it->color.redF(),
00563 point_it->color.greenF(),
00564 point_it->color.blueF(),
00565 point_it->color.alphaF());
00566
00567 glVertex2d(
00568 point_it->transformed_point.getX(),
00569 point_it->transformed_point.getY());
00570 }
00571
00572 glEnd();
00573 }
00574 else if (marker.display_type == visualization_msgs::Marker::CYLINDER ||
00575 marker.display_type == visualization_msgs::Marker::SPHERE ||
00576 marker.display_type == visualization_msgs::Marker::SPHERE_LIST)
00577 {
00578 std::list<StampedPoint>::iterator point_it = marker.points.begin();
00579 for (; point_it != marker.points.end(); ++point_it)
00580 {
00581 glColor4d(
00582 point_it->color.redF(),
00583 point_it->color.greenF(),
00584 point_it->color.blueF(),
00585 point_it->color.alphaF());
00586
00587
00588 glBegin(GL_TRIANGLE_FAN);
00589
00590
00591 double marker_x = point_it->transformed_point.getX();
00592 double marker_y = point_it->transformed_point.getY();
00593
00594 glVertex2d(marker_x, marker_y);
00595
00596 for (int32_t i = 0; i <= 360; i += 10)
00597 {
00598 double radians = static_cast<double>(i) * static_cast<double>(swri_math_util::_deg_2_rad);
00599
00600 if(marker.scale_y == 0.0)
00601 {
00602 marker.scale_y = marker.scale_x;
00603 }
00604 glVertex2d(
00605 marker_x + std::sin(radians) * marker.scale_x,
00606 marker_y + std::cos(radians) * marker.scale_y);
00607 }
00608
00609 glEnd();
00610 }
00611 }
00612 else if (marker.display_type == visualization_msgs::Marker::CUBE ||
00613 marker.display_type == visualization_msgs::Marker::CUBE_LIST)
00614 {
00615 std::list<StampedPoint>::iterator point_it = marker.points.begin();
00616 glBegin(GL_TRIANGLE_FAN);
00617 for (; point_it != marker.points.end(); ++point_it)
00618 {
00619 glColor4d(
00620 point_it->color.redF(),
00621 point_it->color.greenF(),
00622 point_it->color.blueF(),
00623 point_it->color.alphaF());
00624
00625 glVertex2d(point_it->transformed_point.getX(), point_it->transformed_point.getY());
00626 }
00627 glEnd();
00628 }
00629
00630 PrintInfo("OK");
00631 }
00632
00633 ++markerIter;
00634 }
00635 else
00636 {
00637 PrintInfo("OK");
00638 markerIter = nsIter->second.erase(markerIter);
00639 }
00640 }
00641 }
00642 }
00643
00644 void MarkerPlugin::Paint(QPainter* painter, double x, double y, double scale)
00645 {
00646
00647
00648
00649 ros::Time now = ros::Time::now();
00650
00651
00652
00653
00654
00655 QTransform tf = painter->worldTransform();
00656 QFont font("Helvetica", 10);
00657 painter->setFont(font);
00658 painter->save();
00659 painter->resetTransform();
00660
00661 std::map<std::string, std::map<int, MarkerData> >::iterator nsIter;
00662 for (nsIter = markers_.begin(); nsIter != markers_.end(); ++nsIter)
00663 {
00664 std::map<int, MarkerData>::iterator markerIter;
00665 for (markerIter = nsIter->second.begin(); markerIter != nsIter->second.end(); ++markerIter)
00666 {
00667 MarkerData& marker = markerIter->second;
00668
00669 if (marker.display_type != visualization_msgs::Marker::TEXT_VIEW_FACING ||
00670 marker.expire_time <= now ||
00671 !marker.transformed)
00672 {
00673 continue;
00674 }
00675
00676 QPen pen(QBrush(QColor(marker.color.red(), marker.color.green(),
00677 marker.color.blue())), 1);
00678 painter->setPen(pen);
00679
00680 StampedPoint& rosPoint = marker.points.front();
00681 QPointF point = tf.map(QPointF(rosPoint.transformed_point.x(),
00682 rosPoint.transformed_point.y()));
00683
00684
00685 QRectF rect(point, QSizeF(10,10));
00686 rect = painter->boundingRect(rect, Qt::AlignLeft ,QString(marker.text.c_str()));
00687 painter->drawText(rect, QString(marker.text.c_str()));
00688
00689 PrintInfo("OK");
00690 }
00691 }
00692
00693 painter->restore();
00694 }
00695
00696 void MarkerPlugin::Transform()
00697 {
00698 std::map<std::string, std::map<int, MarkerData> >::iterator nsIter;
00699 for (nsIter = markers_.begin(); nsIter != markers_.end(); ++nsIter)
00700 {
00701 std::map<int, MarkerData>::iterator markerIter;
00702 for (markerIter = nsIter->second.begin(); markerIter != nsIter->second.end(); ++markerIter)
00703 {
00704 MarkerData& marker = markerIter->second;
00705
00706 swri_transform_util::Transform transform;
00707 if (GetTransform(marker.source_frame, marker.stamp, transform))
00708 {
00709 marker.transformed = true;
00710
00711 if (marker.display_type == visualization_msgs::Marker::ARROW)
00712 {
00713
00714
00715 transformArrow(marker, transform);
00716 }
00717 else
00718 {
00719 std::list<StampedPoint>::iterator point_it;
00720 for (point_it = marker.points.begin(); point_it != marker.points.end(); ++point_it)
00721 {
00722 point_it->transformed_point = transform * (marker.local_transform * point_it->point);
00723 }
00724 }
00725 }
00726 else
00727 {
00728 marker.transformed = false;
00729 }
00730 }
00731 }
00732 }
00733
00734 void MarkerPlugin::LoadConfig(const YAML::Node& node, const std::string& path)
00735 {
00736 if (node["topic"])
00737 {
00738 std::string topic;
00739 node["topic"] >> topic;
00740 ui_.topic->setText(boost::trim_copy(topic).c_str());
00741
00742 TopicEdited();
00743 }
00744 }
00745
00746 void MarkerPlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path)
00747 {
00748 emitter << YAML::Key << "topic" << YAML::Value << boost::trim_copy(ui_.topic->text().toStdString());
00749 }
00750
00751 void MarkerPlugin::timerEvent(QTimerEvent *event)
00752 {
00753 bool new_connected = (marker_sub_.getNumPublishers() > 0);
00754 if (connected_ && !new_connected)
00755 {
00756 marker_sub_.shutdown();
00757 if (!topic_.empty())
00758 {
00759 marker_sub_ = node_.subscribe<topic_tools::ShapeShifter>(
00760 topic_, 100, &MarkerPlugin::handleMessage, this);
00761 }
00762 }
00763 connected_ = new_connected;
00764 }
00765 }
00766