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
00031
00032
00033
00034
00035
00036
00037
00038
00039 #include <rviz_visual_tools/rviz_visual_tools.h>
00040
00041
00042 #include <tf_conversions/tf_eigen.h>
00043 #include <eigen_conversions/eigen_msg.h>
00044
00045
00046 #include <utility>
00047 #include <string>
00048 #include <vector>
00049 #include <set>
00050 #include <cmath>
00051
00052 namespace rviz_visual_tools
00053 {
00054 RvizVisualTools::RvizVisualTools(const std::string &base_frame, const std::string &marker_topic)
00055 : nh_("~")
00056 , name_("visual_tools")
00057 , marker_topic_(marker_topic)
00058 , base_frame_(base_frame)
00059 , batch_publishing_enabled_(false)
00060 , pub_rviz_markers_connected_(false)
00061 , pub_rviz_markers_waited_(false)
00062 , psychedelic_mode_(false)
00063 {
00064 initialize();
00065 double bug;
00066 }
00067
00068 void RvizVisualTools::initialize()
00069 {
00070 marker_lifetime_ = ros::Duration(0.0);
00071 alpha_ = 1.0;
00072 global_scale_ = 1.0;
00073
00074 loadRvizMarkers();
00075 }
00076
00077 bool RvizVisualTools::deleteAllMarkers()
00078 {
00079
00080 return publishMarker(reset_marker_);
00081 }
00082
00083 void RvizVisualTools::resetMarkerCounts()
00084 {
00085 arrow_marker_.id++;
00086 sphere_marker_.id++;
00087 block_marker_.id++;
00088 cylinder_marker_.id++;
00089 mesh_marker_.id++;
00090 text_marker_.id++;
00091 cuboid_marker_.id++;
00092 line_strip_marker_.id++;
00093 line_list_marker_.id++;
00094 spheres_marker_.id++;
00095 triangle_marker_.id++;
00096 }
00097
00098 bool RvizVisualTools::loadRvizMarkers()
00099 {
00100
00101 reset_marker_.header.frame_id = base_frame_;
00102 reset_marker_.header.stamp = ros::Time();
00103 reset_marker_.action = 3;
00104
00105
00106
00107 arrow_marker_.header.frame_id = base_frame_;
00108
00109
00110 arrow_marker_.ns = "Arrow";
00111
00112 arrow_marker_.type = visualization_msgs::Marker::ARROW;
00113
00114 arrow_marker_.action = visualization_msgs::Marker::ADD;
00115
00116 arrow_marker_.lifetime = marker_lifetime_;
00117
00118
00119
00120 cuboid_marker_.header.frame_id = base_frame_;
00121
00122
00123 cuboid_marker_.ns = "Cuboid";
00124
00125 cuboid_marker_.type = visualization_msgs::Marker::CUBE;
00126
00127 cuboid_marker_.action = visualization_msgs::Marker::ADD;
00128
00129 cuboid_marker_.lifetime = marker_lifetime_;
00130
00131
00132
00133 line_strip_marker_.header.frame_id = base_frame_;
00134
00135
00136 line_strip_marker_.ns = "Line";
00137
00138 line_strip_marker_.type = visualization_msgs::Marker::LINE_STRIP;
00139
00140 line_strip_marker_.action = visualization_msgs::Marker::ADD;
00141
00142 line_strip_marker_.lifetime = marker_lifetime_;
00143
00144
00145
00146 line_list_marker_.header.frame_id = base_frame_;
00147
00148
00149 line_list_marker_.ns = "Line_List";
00150
00151 line_list_marker_.type = visualization_msgs::Marker::LINE_LIST;
00152
00153 line_list_marker_.action = visualization_msgs::Marker::ADD;
00154
00155 line_list_marker_.lifetime = marker_lifetime_;
00156
00157 line_list_marker_.pose.position.x = 0.0;
00158 line_list_marker_.pose.position.y = 0.0;
00159 line_list_marker_.pose.position.z = 0.0;
00160
00161 line_list_marker_.pose.orientation.x = 0.0;
00162 line_list_marker_.pose.orientation.y = 0.0;
00163 line_list_marker_.pose.orientation.z = 0.0;
00164 line_list_marker_.pose.orientation.w = 1.0;
00165
00166
00167
00168 spheres_marker_.header.frame_id = base_frame_;
00169
00170
00171 spheres_marker_.ns = "Spheres";
00172
00173 spheres_marker_.type = visualization_msgs::Marker::SPHERE_LIST;
00174
00175 spheres_marker_.action = visualization_msgs::Marker::ADD;
00176
00177 spheres_marker_.lifetime = marker_lifetime_;
00178
00179 spheres_marker_.pose.position.x = 0.0;
00180 spheres_marker_.pose.position.y = 0.0;
00181 spheres_marker_.pose.position.z = 0.0;
00182
00183 spheres_marker_.pose.orientation.x = 0.0;
00184 spheres_marker_.pose.orientation.y = 0.0;
00185 spheres_marker_.pose.orientation.z = 0.0;
00186 spheres_marker_.pose.orientation.w = 1.0;
00187
00188
00189 block_marker_.header.frame_id = base_frame_;
00190
00191
00192 block_marker_.ns = "Block";
00193
00194 block_marker_.action = visualization_msgs::Marker::ADD;
00195
00196 block_marker_.type = visualization_msgs::Marker::CUBE;
00197
00198 block_marker_.lifetime = marker_lifetime_;
00199
00200
00201 cylinder_marker_.header.frame_id = base_frame_;
00202
00203 cylinder_marker_.action = visualization_msgs::Marker::ADD;
00204
00205 cylinder_marker_.type = visualization_msgs::Marker::CYLINDER;
00206
00207 cylinder_marker_.lifetime = marker_lifetime_;
00208
00209
00210 mesh_marker_.header.frame_id = base_frame_;
00211
00212
00213 mesh_marker_.action = visualization_msgs::Marker::ADD;
00214
00215 mesh_marker_.type = visualization_msgs::Marker::MESH_RESOURCE;
00216
00217 mesh_marker_.lifetime = marker_lifetime_;
00218
00219
00220 sphere_marker_.header.frame_id = base_frame_;
00221
00222
00223 sphere_marker_.ns = "Sphere";
00224
00225 sphere_marker_.type = visualization_msgs::Marker::SPHERE;
00226
00227 sphere_marker_.action = visualization_msgs::Marker::ADD;
00228
00229 sphere_marker_.pose.position.x = 0;
00230 sphere_marker_.pose.position.y = 0;
00231 sphere_marker_.pose.position.z = 0;
00232 sphere_marker_.pose.orientation.x = 0.0;
00233 sphere_marker_.pose.orientation.y = 0.0;
00234 sphere_marker_.pose.orientation.z = 0.0;
00235 sphere_marker_.pose.orientation.w = 1.0;
00236
00237 geometry_msgs::Point point_a;
00238
00239 sphere_marker_.points.push_back(point_a);
00240 sphere_marker_.colors.push_back(getColor(BLUE));
00241
00242 sphere_marker_.lifetime = marker_lifetime_;
00243
00244
00245
00246
00247 text_marker_.ns = "Text";
00248
00249 text_marker_.action = visualization_msgs::Marker::ADD;
00250
00251 text_marker_.type = visualization_msgs::Marker::TEXT_VIEW_FACING;
00252
00253 text_marker_.lifetime = marker_lifetime_;
00254
00255
00256
00257 triangle_marker_.header.frame_id = base_frame_;
00258 triangle_marker_.ns = "Triangle";
00259
00260 triangle_marker_.action = visualization_msgs::Marker::ADD;
00261
00262 triangle_marker_.type = visualization_msgs::Marker::TRIANGLE_LIST;
00263
00264 triangle_marker_.lifetime = marker_lifetime_;
00265
00266 return true;
00267 }
00268
00269 void RvizVisualTools::loadMarkerPub(bool wait_for_subscriber, bool latched)
00270 {
00271 if (pub_rviz_markers_)
00272 return;
00273
00274
00275 pub_rviz_markers_ = nh_.advertise<visualization_msgs::MarkerArray>(marker_topic_, 10, latched);
00276 ROS_DEBUG_STREAM_NAMED(name_, "Publishing Rviz markers on topic " << pub_rviz_markers_.getTopic());
00277
00278 if (wait_for_subscriber)
00279 waitForSubscriber(pub_rviz_markers_);
00280 }
00281
00282 bool RvizVisualTools::waitForSubscriber(const ros::Publisher &pub, const double &wait_time)
00283 {
00284
00285 ros::Time max_time(ros::Time::now() + ros::Duration(wait_time));
00286
00287
00288
00289 int num_existing_subscribers = pub.getNumSubscribers();
00290
00291
00292 ros::Rate poll_rate(200);
00293
00294
00295 while (num_existing_subscribers == 0)
00296 {
00297
00298 if (ros::Time::now() > max_time)
00299 {
00300 ROS_WARN_STREAM_NAMED(name_, "Topic '" << pub.getTopic() << "' unable to connect to any subscribers within "
00301 << wait_time << " sec. It is possible initially published visual messages "
00302 "will be lost.");
00303 return false;
00304 }
00305 ros::spinOnce();
00306
00307
00308 poll_rate.sleep();
00309
00310
00311 num_existing_subscribers = pub.getNumSubscribers();
00312
00313 }
00314 pub_rviz_markers_connected_ = true;
00315
00316 return true;
00317 }
00318
00319 void RvizVisualTools::setFloorToBaseHeight(double floor_to_base_height)
00320 {
00321 ROS_WARN_STREAM_NAMED(name_, "Deperecated function");
00322 }
00323
00324 void RvizVisualTools::setLifetime(double lifetime)
00325 {
00326 marker_lifetime_ = ros::Duration(lifetime);
00327
00328
00329 arrow_marker_.lifetime = marker_lifetime_;
00330 cuboid_marker_.lifetime = marker_lifetime_;
00331 line_strip_marker_.lifetime = marker_lifetime_;
00332 sphere_marker_.lifetime = marker_lifetime_;
00333 block_marker_.lifetime = marker_lifetime_;
00334 mesh_marker_.lifetime = marker_lifetime_;
00335 cylinder_marker_.lifetime = marker_lifetime_;
00336 text_marker_.lifetime = marker_lifetime_;
00337 }
00338
00339 colors RvizVisualTools::getRandColor()
00340 {
00341 std::vector<colors> all_colors;
00342
00343 all_colors.push_back(RED);
00344 all_colors.push_back(GREEN);
00345 all_colors.push_back(BLUE);
00346 all_colors.push_back(GREY);
00347 all_colors.push_back(DARK_GREY);
00348 all_colors.push_back(WHITE);
00349 all_colors.push_back(ORANGE);
00350
00351 all_colors.push_back(YELLOW);
00352 all_colors.push_back(BROWN);
00353 all_colors.push_back(PINK);
00354 all_colors.push_back(LIME_GREEN);
00355 all_colors.push_back(PURPLE);
00356 all_colors.push_back(CYAN);
00357 all_colors.push_back(MAGENTA);
00358
00359 int rand_num = iRand(0, all_colors.size() - 1);
00360 return all_colors[rand_num];
00361 }
00362
00363 std_msgs::ColorRGBA RvizVisualTools::getColor(const colors &color)
00364 {
00365 std_msgs::ColorRGBA result;
00366
00367 switch (color)
00368 {
00369 case RED:
00370 result.r = 0.8;
00371 result.g = 0.1;
00372 result.b = 0.1;
00373 result.a = alpha_;
00374 break;
00375 case GREEN:
00376 result.r = 0.1;
00377 result.g = 0.8;
00378 result.b = 0.1;
00379 result.a = alpha_;
00380 break;
00381 case GREY:
00382 result.r = 0.9;
00383 result.g = 0.9;
00384 result.b = 0.9;
00385 result.a = alpha_;
00386 case DARK_GREY:
00387 result.r = 0.6;
00388 result.g = 0.6;
00389 result.b = 0.6;
00390 result.a = alpha_;
00391 break;
00392 case WHITE:
00393 result.r = 1.0;
00394 result.g = 1.0;
00395 result.b = 1.0;
00396 result.a = alpha_;
00397 break;
00398 case ORANGE:
00399 result.r = 1.0;
00400 result.g = 0.5;
00401 result.b = 0.0;
00402 result.a = alpha_;
00403 break;
00404 case TRANSLUCENT_LIGHT:
00405 result.r = 0.1;
00406 result.g = 0.1;
00407 result.b = 0.1;
00408 result.a = 0.1;
00409 break;
00410 case TRANSLUCENT:
00411 result.r = 0.1;
00412 result.g = 0.1;
00413 result.b = 0.1;
00414 result.a = 0.25;
00415 break;
00416 case TRANSLUCENT_DARK:
00417 result.r = 0.1;
00418 result.g = 0.1;
00419 result.b = 0.1;
00420 result.a = 0.5;
00421 break;
00422 case BLACK:
00423 result.r = 0.0;
00424 result.g = 0.0;
00425 result.b = 0.0;
00426 result.a = alpha_;
00427 break;
00428 case YELLOW:
00429 result.r = 1.0;
00430 result.g = 1.0;
00431 result.b = 0.0;
00432 result.a = alpha_;
00433 break;
00434 case BROWN:
00435 result.r = 0.597;
00436 result.g = 0.296;
00437 result.b = 0.0;
00438 result.a = alpha_;
00439 break;
00440 case PINK:
00441 result.r = 1.0;
00442 result.g = 0.4;
00443 result.b = 1;
00444 result.a = alpha_;
00445 break;
00446 case LIME_GREEN:
00447 result.r = 0.6;
00448 result.g = 1.0;
00449 result.b = 0.2;
00450 result.a = alpha_;
00451 break;
00452 case CLEAR:
00453 result.r = 1.0;
00454 result.g = 1.0;
00455 result.b = 1.0;
00456 result.a = 0.0;
00457 break;
00458 case PURPLE:
00459 result.r = 0.597;
00460 result.g = 0.0;
00461 result.b = 0.597;
00462 result.a = alpha_;
00463 break;
00464 case CYAN:
00465 result.r = 0.0;
00466 result.g = 1.0;
00467 result.b = 1.0;
00468 result.a = alpha_;
00469 break;
00470 case MAGENTA:
00471 result.r = 1.0;
00472 result.g = 0.0;
00473 result.b = 1.0;
00474 result.a = alpha_;
00475 break;
00476 case RAND:
00477 result = createRandColor();
00478 break;
00479 case DEFAULT:
00480 ROS_WARN_STREAM_NAMED(name_, "The 'DEFAULT' color should probably not "
00481 "be used with getColor(). Defaulting to "
00482 "blue.");
00483 case BLUE:
00484 default:
00485 result.r = 0.1;
00486 result.g = 0.1;
00487 result.b = 0.8;
00488 result.a = alpha_;
00489 }
00490
00491 return result;
00492 }
00493
00494 std_msgs::ColorRGBA RvizVisualTools::createRandColor()
00495 {
00496 std_msgs::ColorRGBA result;
00497
00498 const std::size_t MAX_ATTEMPTS = 10;
00499 std::size_t attempts = 0;
00500
00501
00502 do
00503 {
00504 result.r = fRand(0.0, 1.0);
00505 result.g = fRand(0.0, 1.0);
00506 result.b = fRand(0.0, 1.0);
00507
00508
00509 attempts++;
00510 if (attempts > MAX_ATTEMPTS)
00511 {
00512 ROS_WARN_STREAM_NAMED(name_, "Unable to find appropriate random color after " << MAX_ATTEMPTS << " attempts");
00513 break;
00514 }
00515 } while (result.r + result.g + result.b < 1.5);
00516
00517
00518 result.a = alpha_;
00519
00520 return result;
00521 }
00522
00523 double RvizVisualTools::slerp(double start, double end, double range, double value)
00524 {
00525
00526 return start + (((end - start) / range) * value);
00527 }
00528
00529 std_msgs::ColorRGBA RvizVisualTools::getColorScale(double value)
00530 {
00531
00532 if (value < 0)
00533 {
00534 ROS_WARN_STREAM_NAMED(name_, "Intensity value for color scale is below range [0,1], value: " << value);
00535 value = 0;
00536 }
00537 else if (value > 1)
00538 {
00539 ROS_WARN_STREAM_NAMED(name_, "Intensity value for color scale is above range [0,1], value: " << value);
00540 value = 1;
00541 }
00542
00543 std_msgs::ColorRGBA start;
00544 std_msgs::ColorRGBA end;
00545
00546
00547 if (value == 0.0)
00548 return getColor(RED);
00549 else if (value == 1.0)
00550 return getColor(GREEN);
00551 else if (value <= 0.5)
00552 {
00553 start = getColor(RED);
00554 end = getColor(YELLOW);
00555 }
00556 else
00557 {
00558 start = getColor(YELLOW);
00559 end = getColor(GREEN);
00560 value = fmod(value, 0.5);
00561 }
00562
00563 std_msgs::ColorRGBA result;
00564 result.r = slerp(start.r, end.r, 0.5, value);
00565 result.g = slerp(start.g, end.g, 0.5, value);
00566 result.b = slerp(start.b, end.b, 0.5, value);
00567 result.a = alpha_;
00568
00569 return result;
00570 }
00571
00572 geometry_msgs::Vector3 RvizVisualTools::getScale(const scales &scale, bool arrow_scale, double marker_scale)
00573 {
00574 geometry_msgs::Vector3 result;
00575 double val(0.0);
00576 switch (scale)
00577 {
00578 case XXSMALL:
00579 val = 0.005;
00580 break;
00581 case XSMALL:
00582 val = 0.01;
00583 break;
00584 case SMALL:
00585 val = 0.03;
00586 break;
00587 case REGULAR:
00588 val = 0.05;
00589 break;
00590 case LARGE:
00591 val = 0.1;
00592 break;
00593 case xLARGE:
00594 val = 0.2;
00595 break;
00596 case xxLARGE:
00597 val = 0.3;
00598 break;
00599 case xxxLARGE:
00600 val = 0.4;
00601 break;
00602 case XLARGE:
00603 val = 0.5;
00604 break;
00605 case XXLARGE:
00606 val = 1.0;
00607 break;
00608 default:
00609 ROS_ERROR_STREAM_NAMED(name_, "Not implemented yet");
00610 break;
00611 }
00612
00613
00614 result.x = val * marker_scale * global_scale_;
00615 result.y = val * marker_scale * global_scale_;
00616 result.z = val * marker_scale * global_scale_;
00617
00618
00619 if (arrow_scale)
00620 {
00621 result.y *= 0.1;
00622 result.z *= 0.1;
00623 }
00624
00625 return result;
00626 }
00627
00628 Eigen::Vector3d RvizVisualTools::getCenterPoint(Eigen::Vector3d a, Eigen::Vector3d b)
00629 {
00630 Eigen::Vector3d center;
00631 center[0] = (a[0] + b[0]) / 2;
00632 center[1] = (a[1] + b[1]) / 2;
00633 center[2] = (a[2] + b[2]) / 2;
00634 return center;
00635 }
00636
00637 Eigen::Affine3d RvizVisualTools::getVectorBetweenPoints(Eigen::Vector3d a, Eigen::Vector3d b)
00638 {
00639
00640
00641
00642
00643
00644
00645
00646 Eigen::Quaterniond q;
00647
00648 Eigen::Vector3d axis_vector = b - a;
00649 axis_vector.normalize();
00650
00651 Eigen::Vector3d up_vector(0.0, 0.0, 1.0);
00652 Eigen::Vector3d right_axis_vector = axis_vector.cross(up_vector);
00653 right_axis_vector.normalized();
00654 double theta = axis_vector.dot(up_vector);
00655 double angle_rotation = -1.0 * acos(theta);
00656
00657
00658
00659
00660 tf::Vector3 tf_right_axis_vector;
00661 tf::vectorEigenToTF(right_axis_vector, tf_right_axis_vector);
00662
00663
00664 tf::Quaternion tf_q(tf_right_axis_vector, angle_rotation);
00665
00666
00667 tf::quaternionTFToEigen(tf_q, q);
00668
00669
00670
00671
00672
00673
00674
00675
00676
00677
00678 Eigen::Affine3d pose;
00679 q.normalize();
00680 pose = q * Eigen::AngleAxisd(-0.5 * M_PI, Eigen::Vector3d::UnitY());
00681 pose.translation() = a;
00682
00683 return pose;
00684 }
00685
00686 bool RvizVisualTools::publishMarker(visualization_msgs::Marker &marker)
00687 {
00688
00689 markers_.markers.push_back(marker);
00690
00691
00692 if (!batch_publishing_enabled_ && !internal_batch_publishing_enabled_)
00693 {
00694 return triggerBatchPublish();
00695 }
00696
00697 return true;
00698 }
00699
00700 void RvizVisualTools::enableBatchPublishing(bool enable)
00701 {
00702 batch_publishing_enabled_ = enable;
00703 }
00704
00705 bool RvizVisualTools::triggerBatchPublish()
00706 {
00707 bool result = publishMarkers(markers_);
00708
00709 markers_.markers.clear();
00710 return result;
00711 }
00712
00713 bool RvizVisualTools::triggerBatchPublishAndDisable()
00714 {
00715 triggerBatchPublish();
00716 batch_publishing_enabled_ = false;
00717 }
00718
00719 bool RvizVisualTools::publishMarkers(visualization_msgs::MarkerArray &markers)
00720 {
00721 if (!pub_rviz_markers_)
00722 loadMarkerPub();
00723
00724
00725 if (!pub_rviz_markers_waited_ && !pub_rviz_markers_connected_)
00726 {
00727 ROS_DEBUG_STREAM_NAMED(name_, "Waiting for subscribers before publishing markers...");
00728 waitForSubscriber(pub_rviz_markers_);
00729
00730
00731 pub_rviz_markers_waited_ = true;
00732 }
00733
00734
00735 if (markers.markers.empty())
00736 return false;
00737
00738
00739 if (psychedelic_mode_)
00740 {
00741 for (std::size_t i = 0; i < markers.markers.size(); ++i)
00742 {
00743 markers.markers[i].color.r = 1.0 - markers.markers[i].color.r;
00744 markers.markers[i].color.g = 1.0 - markers.markers[i].color.g;
00745 markers.markers[i].color.b = 1.0 - markers.markers[i].color.b;
00746 for (std::size_t j = 0; j < markers.markers[i].colors.size(); ++j)
00747 {
00748 markers.markers[i].colors[j].r = 1.0 - markers.markers[i].colors[j].r;
00749 markers.markers[i].colors[j].g = 1.0 - markers.markers[i].colors[j].g;
00750 markers.markers[i].colors[j].b = 1.0 - markers.markers[i].colors[j].b;
00751 }
00752 }
00753 }
00754
00755
00756 pub_rviz_markers_.publish(markers);
00757 ros::spinOnce();
00758 return true;
00759 }
00760
00761 bool RvizVisualTools::publishCone(const Eigen::Affine3d &pose, double angle, const colors &color, double scale)
00762 {
00763 return publishCone(convertPose(pose), angle, color, scale);
00764 }
00765
00766 bool RvizVisualTools::publishCone(const geometry_msgs::Pose &pose, double angle, const colors &color, double scale)
00767 {
00768 triangle_marker_.header.stamp = ros::Time::now();
00769 triangle_marker_.id++;
00770
00771 triangle_marker_.color = getColor(color);
00772 triangle_marker_.pose = pose;
00773
00774 geometry_msgs::Point p[3];
00775 static const double delta_theta = M_PI / 16.0;
00776 double theta = 0;
00777
00778 for (std::size_t i = 0; i < 32; i++)
00779 {
00780 p[0].x = 0;
00781 p[0].y = 0;
00782 p[0].z = 0;
00783
00784 p[1].x = scale;
00785 p[1].y = scale * cos(theta);
00786 p[1].z = scale * sin(theta);
00787
00788 p[2].x = scale;
00789 p[2].y = scale * cos(theta + delta_theta);
00790 p[2].z = scale * sin(theta + delta_theta);
00791
00792 triangle_marker_.points.push_back(p[0]);
00793 triangle_marker_.points.push_back(p[1]);
00794 triangle_marker_.points.push_back(p[2]);
00795
00796 theta += delta_theta;
00797 }
00798
00799 triangle_marker_.scale.x = 1.0;
00800 triangle_marker_.scale.y = 1.0;
00801 triangle_marker_.scale.z = 1.0;
00802
00803 return publishMarker(triangle_marker_);
00804 }
00805
00806 bool RvizVisualTools::publishXYPlane(const Eigen::Affine3d &pose, const colors &color, double scale)
00807 {
00808 return publishXYPlane(convertPose(pose), color, scale);
00809 }
00810
00811 bool RvizVisualTools::publishXYPlane(const geometry_msgs::Pose &pose, const colors &color, double scale)
00812 {
00813 triangle_marker_.header.stamp = ros::Time::now();
00814 triangle_marker_.id++;
00815
00816 triangle_marker_.color = getColor(color);
00817 triangle_marker_.pose = pose;
00818
00819 geometry_msgs::Point p[4];
00820 p[0].x = 1.0 * scale;
00821 p[0].y = 1.0 * scale;
00822 p[0].z = 0.0;
00823
00824 p[1].x = -1.0 * scale;
00825 p[1].y = 1.0 * scale;
00826 p[1].z = 0.0;
00827
00828 p[2].x = -1.0 * scale;
00829 p[2].y = -1.0 * scale;
00830 p[2].z = 0.0;
00831
00832 p[3].x = 1.0 * scale;
00833 p[3].y = -1.0 * scale;
00834 p[3].z = 0.0;
00835
00836 triangle_marker_.scale.x = 1.0;
00837 triangle_marker_.scale.y = 1.0;
00838 triangle_marker_.scale.z = 1.0;
00839
00840 triangle_marker_.points.clear();
00841 triangle_marker_.points.push_back(p[0]);
00842 triangle_marker_.points.push_back(p[1]);
00843 triangle_marker_.points.push_back(p[2]);
00844
00845 triangle_marker_.points.push_back(p[2]);
00846 triangle_marker_.points.push_back(p[3]);
00847 triangle_marker_.points.push_back(p[0]);
00848
00849 return publishMarker(triangle_marker_);
00850 }
00851
00852 bool RvizVisualTools::publishXZPlane(const Eigen::Affine3d &pose, const colors &color, double scale)
00853 {
00854 return publishXZPlane(convertPose(pose), color, scale);
00855 }
00856
00857 bool RvizVisualTools::publishXZPlane(const geometry_msgs::Pose &pose, const colors &color, double scale)
00858 {
00859 triangle_marker_.header.stamp = ros::Time::now();
00860 triangle_marker_.id++;
00861
00862 triangle_marker_.color = getColor(color);
00863 triangle_marker_.pose = pose;
00864
00865 geometry_msgs::Point p[4];
00866 p[0].x = 1.0 * scale;
00867 p[0].y = 0;
00868 p[0].z = 1.0 * scale;
00869
00870 p[1].x = -1.0 * scale;
00871 p[1].y = 0;
00872 p[1].z = 1.0 * scale;
00873
00874 p[2].x = -1.0 * scale;
00875 p[2].y = 0;
00876 p[2].z = -1.0 * scale;
00877
00878 p[3].x = 1.0 * scale;
00879 p[3].y = 0;
00880 p[3].z = -1.0 * scale;
00881
00882 triangle_marker_.scale.x = 1.0;
00883 triangle_marker_.scale.y = 1.0;
00884 triangle_marker_.scale.z = 1.0;
00885
00886 triangle_marker_.points.clear();
00887 triangle_marker_.points.push_back(p[0]);
00888 triangle_marker_.points.push_back(p[1]);
00889 triangle_marker_.points.push_back(p[2]);
00890
00891 triangle_marker_.points.push_back(p[2]);
00892 triangle_marker_.points.push_back(p[3]);
00893 triangle_marker_.points.push_back(p[0]);
00894
00895 return publishMarker(triangle_marker_);
00896 }
00897
00898 bool RvizVisualTools::publishYZPlane(const Eigen::Affine3d &pose, const colors &color, double scale)
00899 {
00900 return publishYZPlane(convertPose(pose), color, scale);
00901 }
00902
00903 bool RvizVisualTools::publishYZPlane(const geometry_msgs::Pose &pose, const colors &color, double scale)
00904 {
00905 triangle_marker_.header.stamp = ros::Time::now();
00906 triangle_marker_.id++;
00907
00908 triangle_marker_.color = getColor(color);
00909 triangle_marker_.pose = pose;
00910
00911 geometry_msgs::Point p[4];
00912 p[0].x = 0;
00913 p[0].y = 1.0 * scale;
00914 p[0].z = 1.0 * scale;
00915
00916 p[1].x = 0;
00917 p[1].y = -1.0 * scale;
00918 p[1].z = 1.0 * scale;
00919
00920 p[2].x = 0;
00921 p[2].y = -1.0 * scale;
00922 p[2].z = -1.0 * scale;
00923
00924 p[3].x = 0;
00925 p[3].y = 1.0 * scale;
00926 p[3].z = -1.0 * scale;
00927
00928 triangle_marker_.scale.x = 1.0;
00929 triangle_marker_.scale.y = 1.0;
00930 triangle_marker_.scale.z = 1.0;
00931
00932 triangle_marker_.points.clear();
00933 triangle_marker_.points.push_back(p[0]);
00934 triangle_marker_.points.push_back(p[1]);
00935 triangle_marker_.points.push_back(p[2]);
00936
00937 triangle_marker_.points.push_back(p[2]);
00938 triangle_marker_.points.push_back(p[3]);
00939 triangle_marker_.points.push_back(p[0]);
00940
00941 return publishMarker(triangle_marker_);
00942 }
00943
00944 bool RvizVisualTools::publishSphere(const Eigen::Affine3d &pose, const colors &color, const scales &scale,
00945 const std::string &ns, const std::size_t &id)
00946 {
00947 return publishSphere(convertPose(pose), color, scale, ns, id);
00948 }
00949
00950 bool RvizVisualTools::publishSphere(const Eigen::Vector3d &point, const colors &color, const scales &scale,
00951 const std::string &ns, const std::size_t &id)
00952 {
00953 geometry_msgs::Pose pose_msg;
00954 tf::pointEigenToMsg(point, pose_msg.position);
00955 return publishSphere(pose_msg, color, scale, ns, id);
00956 }
00957
00958 bool RvizVisualTools::publishSphere(const Eigen::Vector3d &point, const colors &color, const double scale,
00959 const std::string &ns, const std::size_t &id)
00960 {
00961 geometry_msgs::Pose pose_msg;
00962 tf::pointEigenToMsg(point, pose_msg.position);
00963 return publishSphere(pose_msg, color, scale, ns, id);
00964 }
00965
00966 bool RvizVisualTools::publishSphere(const geometry_msgs::Point &point, const colors &color, const scales &scale,
00967 const std::string &ns, const std::size_t &id)
00968 {
00969 geometry_msgs::Pose pose_msg;
00970 pose_msg.position = point;
00971 return publishSphere(pose_msg, color, scale, ns, id);
00972 }
00973
00974 bool RvizVisualTools::publishSphere(const geometry_msgs::Pose &pose, const colors &color, const scales &scale,
00975 const std::string &ns, const std::size_t &id)
00976 {
00977 return publishSphere(pose, color, getScale(scale, false, 0.1), ns, id);
00978 }
00979
00980 bool RvizVisualTools::publishSphere(const geometry_msgs::Pose &pose, const colors &color, double scale,
00981 const std::string &ns, const std::size_t &id)
00982 {
00983 geometry_msgs::Vector3 scale_msg;
00984 scale_msg.x = scale;
00985 scale_msg.y = scale;
00986 scale_msg.z = scale;
00987 return publishSphere(pose, color, scale_msg, ns, id);
00988 }
00989
00990 bool RvizVisualTools::publishSphere(const geometry_msgs::Pose &pose, const colors &color,
00991 const geometry_msgs::Vector3 scale, const std::string &ns, const std::size_t &id)
00992 {
00993 return publishSphere(pose, getColor(color), scale, ns, id);
00994 }
00995
00996 bool RvizVisualTools::publishSphere(const Eigen::Affine3d &pose, const std_msgs::ColorRGBA &color,
00997 const geometry_msgs::Vector3 scale, const std::string &ns, const std::size_t &id)
00998 {
00999 return publishSphere(convertPose(pose), color, scale, ns, id);
01000 }
01001
01002 bool RvizVisualTools::publishSphere(const geometry_msgs::Pose &pose, const std_msgs::ColorRGBA &color,
01003 const geometry_msgs::Vector3 scale, const std::string &ns, const std::size_t &id)
01004 {
01005
01006 sphere_marker_.header.stamp = ros::Time::now();
01007
01008
01009 if (id == 0)
01010 sphere_marker_.id++;
01011 else
01012 sphere_marker_.id = id;
01013
01014 sphere_marker_.pose = pose;
01015 sphere_marker_.color = color;
01016 sphere_marker_.scale = scale;
01017 sphere_marker_.ns = ns;
01018
01019
01020 return publishMarker(sphere_marker_);
01021 }
01022
01023 bool RvizVisualTools::publishSphere(const geometry_msgs::PoseStamped &pose, const colors &color,
01024 const geometry_msgs::Vector3 scale, const std::string &ns, const std::size_t &id)
01025 {
01026
01027 sphere_marker_.header = pose.header;
01028
01029 if (id == 0)
01030 sphere_marker_.id++;
01031 else
01032 sphere_marker_.id = id;
01033
01034 sphere_marker_.pose = pose.pose;
01035 sphere_marker_.color = getColor(color);
01036 sphere_marker_.scale = scale;
01037 sphere_marker_.ns = ns;
01038
01039
01040 publishMarker(sphere_marker_);
01041
01042 sphere_marker_.header.frame_id = base_frame_;
01043 return true;
01044 }
01045
01046 bool RvizVisualTools::publishXArrow(const Eigen::Affine3d &pose, const colors &color, const scales &scale,
01047 double length)
01048 {
01049 return publishArrow(convertPose(pose), color, scale, length);
01050 }
01051
01052 bool RvizVisualTools::publishXArrow(const geometry_msgs::Pose &pose, const colors &color, const scales &scale,
01053 double length)
01054 {
01055 return publishArrow(pose, color, scale, length);
01056 }
01057
01058 bool RvizVisualTools::publishXArrow(const geometry_msgs::PoseStamped &pose, const colors &color, const scales &scale,
01059 double length)
01060 {
01061 return publishArrow(pose, color, scale, length);
01062 }
01063
01064 bool RvizVisualTools::publishYArrow(const Eigen::Affine3d &pose, const colors &color, const scales &scale,
01065 double length)
01066 {
01067 Eigen::Affine3d arrow_pose = pose * Eigen::AngleAxisd(M_PI / 2, Eigen::Vector3d::UnitZ());
01068 return publishArrow(convertPose(arrow_pose), color, scale, length);
01069 }
01070
01071 bool RvizVisualTools::publishYArrow(const geometry_msgs::Pose &pose, const colors &color, const scales &scale,
01072 double length)
01073 {
01074 Eigen::Affine3d arrow_pose = convertPose(pose) * Eigen::AngleAxisd(M_PI / 2, Eigen::Vector3d::UnitZ());
01075 return publishArrow(convertPose(arrow_pose), color, scale, length);
01076 }
01077
01078 bool RvizVisualTools::publishYArrow(const geometry_msgs::PoseStamped &pose, const colors &color, const scales &scale,
01079 double length)
01080 {
01081 Eigen::Affine3d arrow_pose = convertPose(pose.pose) * Eigen::AngleAxisd(M_PI / 2, Eigen::Vector3d::UnitZ());
01082 geometry_msgs::PoseStamped new_pose = pose;
01083 new_pose.pose = convertPose(arrow_pose);
01084 return publishArrow(new_pose, color, scale, length);
01085 }
01086
01087 bool RvizVisualTools::publishZArrow(const Eigen::Affine3d &pose, const colors &color, const scales &scale,
01088 double length, const std::size_t &id)
01089 {
01090 Eigen::Affine3d arrow_pose = pose * Eigen::AngleAxisd(-M_PI / 2, Eigen::Vector3d::UnitY());
01091 return publishArrow(convertPose(arrow_pose), color, scale, length, id);
01092 }
01093
01094 bool RvizVisualTools::publishZArrow(const geometry_msgs::Pose &pose, const colors &color, const scales &scale,
01095 double length)
01096 {
01097 Eigen::Affine3d arrow_pose = convertPose(pose) * Eigen::AngleAxisd(-M_PI / 2, Eigen::Vector3d::UnitY());
01098 return publishArrow(convertPose(arrow_pose), color, scale, length);
01099 }
01100
01101 bool RvizVisualTools::publishZArrow(const geometry_msgs::PoseStamped &pose, const colors &color, const scales &scale,
01102 double length)
01103 {
01104 Eigen::Affine3d arrow_pose = convertPose(pose.pose) * Eigen::AngleAxisd(-M_PI / 2, Eigen::Vector3d::UnitY());
01105 geometry_msgs::PoseStamped new_pose = pose;
01106 new_pose.pose = convertPose(arrow_pose);
01107 return publishArrow(new_pose, color, scale, length);
01108 }
01109
01110 bool RvizVisualTools::publishZArrow(const geometry_msgs::PoseStamped &pose, const colors &color, const scales &scale,
01111 double length, const std::size_t &id)
01112 {
01113 Eigen::Affine3d arrow_pose = convertPose(pose.pose) * Eigen::AngleAxisd(-M_PI / 2, Eigen::Vector3d::UnitY());
01114 geometry_msgs::PoseStamped new_pose = pose;
01115 new_pose.pose = convertPose(arrow_pose);
01116 return publishArrow(new_pose, color, scale, length, id);
01117 }
01118
01119 bool RvizVisualTools::publishArrow(const Eigen::Affine3d &pose, const colors &color, const scales &scale, double length,
01120 const std::size_t &id)
01121 {
01122 return publishArrow(convertPose(pose), color, scale, length, id);
01123 }
01124
01125 bool RvizVisualTools::publishArrow(const geometry_msgs::Pose &pose, const colors &color, const scales &scale,
01126 double length, const std::size_t &id)
01127 {
01128
01129 arrow_marker_.header.stamp = ros::Time::now();
01130 arrow_marker_.header.frame_id = base_frame_;
01131
01132 if (id == 0)
01133 arrow_marker_.id++;
01134 else
01135 arrow_marker_.id = id;
01136
01137 arrow_marker_.pose = pose;
01138 arrow_marker_.color = getColor(color);
01139 arrow_marker_.scale = getScale(scale, true);
01140 arrow_marker_.scale.x = length;
01141
01142
01143 return publishMarker(arrow_marker_);
01144 }
01145
01146 bool RvizVisualTools::publishArrow(const geometry_msgs::PoseStamped &pose, const colors &color, const scales &scale,
01147 double length, const std::size_t &id)
01148 {
01149
01150 arrow_marker_.header = pose.header;
01151
01152 if (id == 0)
01153 arrow_marker_.id++;
01154 else
01155 arrow_marker_.id = id;
01156
01157 arrow_marker_.pose = pose.pose;
01158 arrow_marker_.color = getColor(color);
01159 arrow_marker_.scale = getScale(scale, true);
01160 arrow_marker_.scale.x = length;
01161
01162
01163 publishMarker(arrow_marker_);
01164
01165 arrow_marker_.header.frame_id = base_frame_;
01166 }
01167
01168 bool RvizVisualTools::publishBlock(const geometry_msgs::Pose &pose, const colors &color, const double &block_size)
01169 {
01170
01171 block_marker_.header.stamp = ros::Time::now();
01172
01173 block_marker_.id++;
01174
01175
01176 block_marker_.pose = pose;
01177
01178
01179 block_marker_.scale.x = block_size;
01180 block_marker_.scale.y = block_size;
01181 block_marker_.scale.z = block_size;
01182
01183
01184 block_marker_.color = getColor(color);
01185
01186
01187 return publishMarker(block_marker_);
01188 }
01189
01190 bool RvizVisualTools::publishBlock(const Eigen::Affine3d &pose, const colors &color, const double &block_size)
01191 {
01192 return publishBlock(convertPose(pose), color, block_size);
01193 }
01194
01195 bool RvizVisualTools::publishAxisLabeled(const Eigen::Affine3d &pose, const std::string &label, const scales &scale, const colors &color)
01196 {
01197 return publishAxisLabeled(convertPose(pose), label, scale, color);
01198 }
01199
01200 bool RvizVisualTools::publishAxisLabeled(const geometry_msgs::Pose &pose, const std::string &label, const scales &scale, const colors &color)
01201 {
01202 publishAxis(pose, 0.1, 0.01, label);
01203
01204 geometry_msgs::Pose pose_shifted = pose;
01205 pose_shifted.position.y -= 0.05;
01206 publishText(pose_shifted, label, color, scale, false);
01207 return true;
01208 }
01209
01210 bool RvizVisualTools::publishAxis(const geometry_msgs::Pose &pose, double length, double radius, const std::string &ns)
01211 {
01212 return publishAxis(convertPose(pose), length, radius, ns);
01213 }
01214
01215 bool RvizVisualTools::publishAxis(const Eigen::Affine3d &pose, double length, double radius, const std::string &ns)
01216 {
01217
01218 enableInternalBatchPublishing(true);
01219
01220
01221 Eigen::Affine3d x_pose =
01222 Eigen::Translation3d(length / 2.0, 0, 0) * Eigen::AngleAxisd(M_PI / 2.0, Eigen::Vector3d::UnitY());
01223 x_pose = pose * x_pose;
01224 publishCylinder(x_pose, rviz_visual_tools::RED, length, radius, ns);
01225
01226
01227 Eigen::Affine3d y_pose =
01228 Eigen::Translation3d(0, length / 2.0, 0) * Eigen::AngleAxisd(M_PI / 2.0, Eigen::Vector3d::UnitX());
01229 y_pose = pose * y_pose;
01230 publishCylinder(y_pose, rviz_visual_tools::GREEN, length, radius, ns);
01231
01232
01233 Eigen::Affine3d z_pose = Eigen::Translation3d(0, 0, length / 2.0) * Eigen::AngleAxisd(0, Eigen::Vector3d::UnitZ());
01234 z_pose = pose * z_pose;
01235 publishCylinder(z_pose, rviz_visual_tools::BLUE, length, radius, ns);
01236
01237
01238 return triggerInternalBatchPublishAndDisable();
01239 }
01240
01241 bool RvizVisualTools::publishCylinder(const Eigen::Vector3d &point1, const Eigen::Vector3d &point2,
01242 const colors &color, double radius, const std::string &ns)
01243 {
01244 return publishCylinder(point1, point2, getColor(color), radius, ns);
01245 }
01246
01247 bool RvizVisualTools::publishCylinder(const Eigen::Vector3d &point1, const Eigen::Vector3d &point2,
01248 const std_msgs::ColorRGBA &color, double radius, const std::string &ns)
01249 {
01250
01251 double height = (point1 - point2).lpNorm<2>();
01252
01253
01254 Eigen::Vector3d pt_center = getCenterPoint(point1, point2);
01255
01256
01257 Eigen::Affine3d pose;
01258 pose = getVectorBetweenPoints(pt_center, point2);
01259
01260
01261 Eigen::Affine3d rotation;
01262 rotation = Eigen::AngleAxisd(0.5 * M_PI, Eigen::Vector3d::UnitY());
01263 pose = pose * rotation;
01264
01265
01266 publishCylinder(convertPose(pose), color, height, radius);
01267 }
01268
01269 bool RvizVisualTools::publishCylinder(const Eigen::Affine3d &pose, const colors &color, double height, double radius,
01270 const std::string &ns)
01271 {
01272 return publishCylinder(convertPose(pose), color, height, radius, ns);
01273 }
01274
01275 bool RvizVisualTools::publishCylinder(const geometry_msgs::Pose &pose, const colors &color, double height,
01276 double radius, const std::string &ns)
01277 {
01278 return publishCylinder(pose, getColor(color), height, radius, ns);
01279 }
01280
01281 bool RvizVisualTools::publishCylinder(const geometry_msgs::Pose &pose, const std_msgs::ColorRGBA &color, double height,
01282 double radius, const std::string &ns)
01283 {
01284
01285 cylinder_marker_.header.stamp = ros::Time::now();
01286 cylinder_marker_.ns = ns;
01287 cylinder_marker_.id++;
01288
01289
01290 cylinder_marker_.pose = pose;
01291
01292
01293 cylinder_marker_.scale.x = radius;
01294 cylinder_marker_.scale.y = radius;
01295 cylinder_marker_.scale.z = height;
01296
01297
01298 cylinder_marker_.color = color;
01299
01300
01301 return publishMarker(cylinder_marker_);
01302 }
01303
01304 bool RvizVisualTools::publishMesh(const Eigen::Affine3d &pose, const std::string &file_name, const colors &color,
01305 double scale, const std::string &ns, const std::size_t &id)
01306 {
01307 return publishMesh(convertPose(pose), file_name, color, scale, ns, id);
01308 }
01309
01310 bool RvizVisualTools::publishMesh(const geometry_msgs::Pose &pose, const std::string &file_name, const colors &color,
01311 double scale, const std::string &ns, const std::size_t &id)
01312 {
01313
01314 mesh_marker_.header.stamp = ros::Time::now();
01315
01316 if (id == 0)
01317 mesh_marker_.id++;
01318 else
01319 mesh_marker_.id = id;
01320
01321
01322 mesh_marker_.mesh_resource = file_name;
01323 mesh_marker_.mesh_use_embedded_materials = true;
01324
01325
01326 mesh_marker_.pose = pose;
01327
01328
01329 mesh_marker_.scale.x = scale;
01330 mesh_marker_.scale.y = scale;
01331 mesh_marker_.scale.z = scale;
01332
01333
01334
01335 mesh_marker_.ns = ns;
01336
01337
01338 mesh_marker_.color = getColor(color);
01339
01340
01341 return publishMarker(mesh_marker_);
01342 }
01343
01344 bool RvizVisualTools::publishGraph(const graph_msgs::GeometryGraph &graph, const colors &color, double radius)
01345 {
01346
01347
01348 typedef std::pair<std::size_t, std::size_t> node_ids;
01349 std::set<node_ids> added_edges;
01350 std::pair<std::set<node_ids>::iterator, bool> return_value;
01351 Eigen::Vector3d a, b;
01352 for (std::size_t i = 0; i < graph.nodes.size(); ++i)
01353 {
01354 for (std::size_t j = 0; j < graph.edges[i].node_ids.size(); ++j)
01355 {
01356
01357 return_value = added_edges.insert(node_ids(i, j));
01358 if (return_value.second == false)
01359 {
01360
01361 }
01362 else
01363 {
01364
01365 a = convertPoint(graph.nodes[i]);
01366 b = convertPoint(graph.nodes[graph.edges[i].node_ids[j]]);
01367
01368 publishCylinder(a, b, color, radius);
01369 }
01370 }
01371 }
01372
01373 return true;
01374 }
01375
01376 bool RvizVisualTools::publishCuboid(const Eigen::Vector3d &point1, const Eigen::Vector3d &point2, const colors &color)
01377 {
01378 return publishCuboid(convertPoint(point1), convertPoint(point2), color);
01379 }
01380
01381 bool RvizVisualTools::publishCuboid(const geometry_msgs::Point &point1, const geometry_msgs::Point &point2,
01382 const colors &color, const std::string &ns, const std::size_t &id)
01383 {
01384
01385 cuboid_marker_.header.stamp = ros::Time::now();
01386 cuboid_marker_.ns = ns;
01387
01388 if (id == 0)
01389 cuboid_marker_.id++;
01390 else
01391 cuboid_marker_.id = id;
01392
01393 cuboid_marker_.color = getColor(color);
01394
01395
01396 geometry_msgs::Pose pose;
01397 pose.position.x = (point1.x - point2.x) / 2.0 + point2.x;
01398 pose.position.y = (point1.y - point2.y) / 2.0 + point2.y;
01399 pose.position.z = (point1.z - point2.z) / 2.0 + point2.z;
01400 cuboid_marker_.pose = pose;
01401
01402
01403 cuboid_marker_.scale.x = fabs(point1.x - point2.x);
01404 cuboid_marker_.scale.y = fabs(point1.y - point2.y);
01405 cuboid_marker_.scale.z = fabs(point1.z - point2.z);
01406
01407
01408 if (!cuboid_marker_.scale.x)
01409 cuboid_marker_.scale.x = SMALL_SCALE;
01410 if (!cuboid_marker_.scale.y)
01411 cuboid_marker_.scale.y = SMALL_SCALE;
01412 if (!cuboid_marker_.scale.z)
01413 cuboid_marker_.scale.z = SMALL_SCALE;
01414
01415
01416 return publishMarker(cuboid_marker_);
01417 }
01418
01419 bool RvizVisualTools::publishCuboid(const Eigen::Affine3d &pose, const double depth, const double width,
01420 const double height, const colors &color)
01421 {
01422 return publishCuboid(convertPose(pose), depth, width, height, color);
01423 }
01424
01425 bool RvizVisualTools::publishCuboid(const geometry_msgs::Pose &pose, const double depth, const double width,
01426 const double height, const colors &color)
01427 {
01428 cuboid_marker_.header.stamp = ros::Time::now();
01429
01430 cuboid_marker_.id++;
01431 cuboid_marker_.color = getColor(color);
01432
01433 cuboid_marker_.pose = pose;
01434
01435
01436 if (depth <= 0)
01437 cuboid_marker_.scale.x = SMALL_SCALE;
01438 else
01439 cuboid_marker_.scale.x = depth;
01440
01441 if (width <= 0)
01442 cuboid_marker_.scale.y = SMALL_SCALE;
01443 else
01444 cuboid_marker_.scale.y = width;
01445
01446 if (height <= 0)
01447 cuboid_marker_.scale.z = SMALL_SCALE;
01448 else
01449 cuboid_marker_.scale.z = height;
01450
01451 return publishMarker(cuboid_marker_);
01452 }
01453
01454 bool RvizVisualTools::publishLine(const Eigen::Affine3d &point1, const Eigen::Affine3d &point2, const colors &color,
01455 const scales &scale)
01456 {
01457 return publishLine(convertPoseToPoint(point1), convertPoseToPoint(point2), color, scale);
01458 }
01459
01460 bool RvizVisualTools::publishLine(const Eigen::Vector3d &point1, const Eigen::Vector3d &point2, const colors &color,
01461 const scales &scale)
01462 {
01463 return publishLine(convertPoint(point1), convertPoint(point2), color, scale);
01464 }
01465
01466 bool RvizVisualTools::publishLine(const Eigen::Vector3d &point1, const Eigen::Vector3d &point2,
01467 const std_msgs::ColorRGBA &color, const scales &scale)
01468 {
01469 return publishLine(convertPoint(point1), convertPoint(point2), color, scale);
01470 }
01471
01472 bool RvizVisualTools::publishLine(const Eigen::Vector3d &point1, const Eigen::Vector3d &point2,
01473 const std_msgs::ColorRGBA &color, const double &radius)
01474 {
01475 geometry_msgs::Vector3 scale;
01476 scale.x = radius;
01477 scale.y = radius;
01478 scale.z = radius;
01479 return publishLine(convertPoint(point1), convertPoint(point2), color, scale);
01480 }
01481
01482 bool RvizVisualTools::publishLine(const geometry_msgs::Point &point1, const geometry_msgs::Point &point2,
01483 const colors &color, const scales &scale)
01484 {
01485 return publishLine(point1, point2, getColor(color), scale);
01486 }
01487
01488 bool RvizVisualTools::publishLine(const geometry_msgs::Point &point1, const geometry_msgs::Point &point2,
01489 const std_msgs::ColorRGBA &color, const scales &scale)
01490 {
01491 return publishLine(point1, point2, color, getScale(scale, false, 0.1));
01492 }
01493
01494 bool RvizVisualTools::publishLine(const geometry_msgs::Point &point1, const geometry_msgs::Point &point2,
01495 const std_msgs::ColorRGBA &color, const geometry_msgs::Vector3 &scale)
01496 {
01497
01498 line_strip_marker_.header.stamp = ros::Time::now();
01499
01500 line_strip_marker_.id++;
01501 line_strip_marker_.color = color;
01502 line_strip_marker_.scale = scale;
01503
01504 line_strip_marker_.points.clear();
01505 line_strip_marker_.points.push_back(point1);
01506 line_strip_marker_.points.push_back(point2);
01507
01508
01509 return publishMarker(line_strip_marker_);
01510 }
01511
01512 bool RvizVisualTools::publishPath(const std::vector<geometry_msgs::Point> &path, const colors &color,
01513 const scales &scale, const std::string &ns)
01514 {
01515 if (path.size() < 2)
01516 {
01517 ROS_WARN_STREAM_NAMED(name_, "Skipping path because " << path.size() << " points passed in.");
01518 return true;
01519 }
01520
01521 line_strip_marker_.header.stamp = ros::Time();
01522 line_strip_marker_.ns = ns;
01523
01524
01525 line_strip_marker_.id++;
01526
01527 std_msgs::ColorRGBA this_color = getColor(color);
01528 line_strip_marker_.scale = getScale(scale, false, 0.25);
01529 line_strip_marker_.color = this_color;
01530 line_strip_marker_.points.clear();
01531 line_strip_marker_.colors.clear();
01532
01533 for (std::size_t i = 1; i < path.size(); ++i)
01534 {
01535
01536 line_strip_marker_.points.push_back(path[i - 1]);
01537 line_strip_marker_.points.push_back(path[i]);
01538 line_strip_marker_.colors.push_back(this_color);
01539 line_strip_marker_.colors.push_back(this_color);
01540 }
01541
01542
01543 return publishMarker(line_strip_marker_);
01544 }
01545
01546 bool RvizVisualTools::publishPath(const std::vector<Eigen::Vector3d> &path, const colors &color,
01547 const double radius, const std::string &ns)
01548 {
01549 if (path.size() < 2)
01550 {
01551 ROS_WARN_STREAM_NAMED(name_, "Skipping path because " << path.size() << " points passed in.");
01552 return true;
01553 }
01554
01555
01556 enableInternalBatchPublishing(true);
01557
01558
01559 for (std::size_t i = 1; i < path.size(); ++i)
01560 {
01561 publishCylinder(path[i - 1], path[i], color, radius, ns);
01562 }
01563
01564
01565 return triggerInternalBatchPublishAndDisable();
01566 }
01567
01568 bool RvizVisualTools::publishPolygon(const geometry_msgs::Polygon &polygon, const colors &color, const scales &scale,
01569 const std::string &ns)
01570 {
01571 std::vector<geometry_msgs::Point> points;
01572 geometry_msgs::Point temp;
01573 geometry_msgs::Point first;
01574
01575
01576 for (std::size_t i = 0; i < polygon.points.size(); ++i)
01577 {
01578 temp.x = polygon.points[i].x;
01579 temp.y = polygon.points[i].y;
01580 temp.z = polygon.points[i].z;
01581 if (i == 0)
01582 first = temp;
01583 points.push_back(temp);
01584 }
01585 points.push_back(first);
01586
01587 publishPath(points, color, scale, ns);
01588 }
01589
01590 bool RvizVisualTools::publishWireframeCuboid(const Eigen::Affine3d &pose, double depth, double width, double height,
01591 const colors &color, const std::string &ns, const std::size_t &id)
01592 {
01593 Eigen::Vector3d min_point, max_point;
01594 min_point << -depth / 2, -width / 2, -height / 2;
01595 max_point << depth / 2, width / 2, height / 2;
01596 return publishWireframeCuboid(pose, min_point, max_point, color, ns, id);
01597 }
01598
01599 bool RvizVisualTools::publishWireframeCuboid(const Eigen::Affine3d &pose, const Eigen::Vector3d &min_point,
01600 const Eigen::Vector3d &max_point, const colors &color,
01601 const std::string &ns, const std::size_t &id)
01602 {
01603
01604 Eigen::Vector3d p1(min_point[0], min_point[1], min_point[2]);
01605 Eigen::Vector3d p2(min_point[0], min_point[1], max_point[2]);
01606 Eigen::Vector3d p3(max_point[0], min_point[1], max_point[2]);
01607 Eigen::Vector3d p4(max_point[0], min_point[1], min_point[2]);
01608 Eigen::Vector3d p5(min_point[0], max_point[1], min_point[2]);
01609 Eigen::Vector3d p6(min_point[0], max_point[1], max_point[2]);
01610 Eigen::Vector3d p7(max_point[0], max_point[1], max_point[2]);
01611 Eigen::Vector3d p8(max_point[0], max_point[1], min_point[2]);
01612
01613 p1 = pose * p1;
01614 p2 = pose * p2;
01615 p3 = pose * p3;
01616 p4 = pose * p4;
01617 p5 = pose * p5;
01618 p6 = pose * p6;
01619 p7 = pose * p7;
01620 p8 = pose * p8;
01621
01622
01623 line_list_marker_.header.stamp = ros::Time();
01624 line_list_marker_.ns = ns;
01625
01626 if (id == 0)
01627 line_list_marker_.id++;
01628 else
01629 line_list_marker_.id = id;
01630
01631 std_msgs::ColorRGBA this_color = getColor(color);
01632 line_list_marker_.scale = getScale(XXSMALL);
01633 line_list_marker_.color = this_color;
01634 line_list_marker_.points.clear();
01635 line_list_marker_.colors.clear();
01636
01637
01638 line_list_marker_.points.push_back(convertPoint(p1));
01639 line_list_marker_.points.push_back(convertPoint(p2));
01640 line_list_marker_.colors.push_back(this_color);
01641 line_list_marker_.colors.push_back(this_color);
01642
01643 line_list_marker_.points.push_back(convertPoint(p1));
01644 line_list_marker_.points.push_back(convertPoint(p4));
01645 line_list_marker_.colors.push_back(this_color);
01646 line_list_marker_.colors.push_back(this_color);
01647
01648 line_list_marker_.points.push_back(convertPoint(p1));
01649 line_list_marker_.points.push_back(convertPoint(p5));
01650 line_list_marker_.colors.push_back(this_color);
01651 line_list_marker_.colors.push_back(this_color);
01652
01653 line_list_marker_.points.push_back(convertPoint(p5));
01654 line_list_marker_.points.push_back(convertPoint(p6));
01655 line_list_marker_.colors.push_back(this_color);
01656 line_list_marker_.colors.push_back(this_color);
01657
01658 line_list_marker_.points.push_back(convertPoint(p5));
01659 line_list_marker_.points.push_back(convertPoint(p8));
01660 line_list_marker_.colors.push_back(this_color);
01661 line_list_marker_.colors.push_back(this_color);
01662
01663 line_list_marker_.points.push_back(convertPoint(p2));
01664 line_list_marker_.points.push_back(convertPoint(p6));
01665 line_list_marker_.colors.push_back(this_color);
01666 line_list_marker_.colors.push_back(this_color);
01667
01668 line_list_marker_.points.push_back(convertPoint(p6));
01669 line_list_marker_.points.push_back(convertPoint(p7));
01670 line_list_marker_.colors.push_back(this_color);
01671 line_list_marker_.colors.push_back(this_color);
01672
01673 line_list_marker_.points.push_back(convertPoint(p7));
01674 line_list_marker_.points.push_back(convertPoint(p8));
01675 line_list_marker_.colors.push_back(this_color);
01676 line_list_marker_.colors.push_back(this_color);
01677
01678 line_list_marker_.points.push_back(convertPoint(p2));
01679 line_list_marker_.points.push_back(convertPoint(p3));
01680 line_list_marker_.colors.push_back(this_color);
01681 line_list_marker_.colors.push_back(this_color);
01682
01683 line_list_marker_.points.push_back(convertPoint(p4));
01684 line_list_marker_.points.push_back(convertPoint(p8));
01685 line_list_marker_.colors.push_back(this_color);
01686 line_list_marker_.colors.push_back(this_color);
01687
01688 line_list_marker_.points.push_back(convertPoint(p3));
01689 line_list_marker_.points.push_back(convertPoint(p4));
01690 line_list_marker_.colors.push_back(this_color);
01691 line_list_marker_.colors.push_back(this_color);
01692
01693 line_list_marker_.points.push_back(convertPoint(p3));
01694 line_list_marker_.points.push_back(convertPoint(p7));
01695 line_list_marker_.colors.push_back(this_color);
01696 line_list_marker_.colors.push_back(this_color);
01697
01698
01699 return publishMarker(line_list_marker_);
01700 }
01701
01702 bool RvizVisualTools::publishWireframeRectangle(const Eigen::Affine3d &pose, const double &height, const double &width,
01703 const colors &color, const scales &scale)
01704 {
01705
01706 Eigen::Vector3d p1(-width / 2.0, -height / 2.0, 0.0);
01707 Eigen::Vector3d p2(-width / 2.0, height / 2.0, 0.0);
01708 Eigen::Vector3d p3(width / 2.0, height / 2.0, 0.0);
01709 Eigen::Vector3d p4(width / 2.0, -height / 2.0, 0.0);
01710
01711 p1 = pose * p1;
01712 p2 = pose * p2;
01713 p3 = pose * p3;
01714 p4 = pose * p4;
01715
01716
01717 line_list_marker_.header.stamp = ros::Time();
01718 line_list_marker_.ns = "Wireframe Rectangle";
01719
01720
01721 line_list_marker_.id++;
01722
01723 std_msgs::ColorRGBA this_color = getColor(color);
01724 line_list_marker_.scale = getScale(scale, false, 0.25);
01725 line_list_marker_.color = this_color;
01726 line_list_marker_.points.clear();
01727 line_list_marker_.colors.clear();
01728
01729
01730 line_list_marker_.points.push_back(convertPoint(p1));
01731 line_list_marker_.points.push_back(convertPoint(p2));
01732 line_list_marker_.colors.push_back(this_color);
01733 line_list_marker_.colors.push_back(this_color);
01734
01735 line_list_marker_.points.push_back(convertPoint(p2));
01736 line_list_marker_.points.push_back(convertPoint(p3));
01737 line_list_marker_.colors.push_back(this_color);
01738 line_list_marker_.colors.push_back(this_color);
01739
01740 line_list_marker_.points.push_back(convertPoint(p3));
01741 line_list_marker_.points.push_back(convertPoint(p4));
01742 line_list_marker_.colors.push_back(this_color);
01743 line_list_marker_.colors.push_back(this_color);
01744
01745 line_list_marker_.points.push_back(convertPoint(p4));
01746 line_list_marker_.points.push_back(convertPoint(p1));
01747 line_list_marker_.colors.push_back(this_color);
01748 line_list_marker_.colors.push_back(this_color);
01749
01750
01751 return publishMarker(line_list_marker_);
01752 }
01753
01754 bool RvizVisualTools::publishWireframeRectangle(const Eigen::Affine3d &pose, const Eigen::Vector3d &p1_in,
01755 const Eigen::Vector3d &p2_in, const Eigen::Vector3d &p3_in,
01756 const Eigen::Vector3d &p4_in, const colors &color, const scales &scale)
01757 {
01758 Eigen::Vector3d p1;
01759 Eigen::Vector3d p2;
01760 Eigen::Vector3d p3;
01761 Eigen::Vector3d p4;
01762
01763
01764 p1 = pose * p1_in;
01765 p2 = pose * p2_in;
01766 p3 = pose * p3_in;
01767 p4 = pose * p4_in;
01768
01769
01770 line_list_marker_.header.stamp = ros::Time();
01771 line_list_marker_.ns = "Wireframe Rectangle";
01772
01773
01774 line_list_marker_.id++;
01775
01776 std_msgs::ColorRGBA this_color = getColor(color);
01777 line_list_marker_.scale = getScale(scale, false, 0.25);
01778 line_list_marker_.color = this_color;
01779 line_list_marker_.points.clear();
01780 line_list_marker_.colors.clear();
01781
01782
01783 line_list_marker_.points.push_back(convertPoint(p1));
01784 line_list_marker_.points.push_back(convertPoint(p2));
01785 line_list_marker_.colors.push_back(this_color);
01786 line_list_marker_.colors.push_back(this_color);
01787
01788 line_list_marker_.points.push_back(convertPoint(p2));
01789 line_list_marker_.points.push_back(convertPoint(p3));
01790 line_list_marker_.colors.push_back(this_color);
01791 line_list_marker_.colors.push_back(this_color);
01792
01793 line_list_marker_.points.push_back(convertPoint(p3));
01794 line_list_marker_.points.push_back(convertPoint(p4));
01795 line_list_marker_.colors.push_back(this_color);
01796 line_list_marker_.colors.push_back(this_color);
01797
01798 line_list_marker_.points.push_back(convertPoint(p4));
01799 line_list_marker_.points.push_back(convertPoint(p1));
01800 line_list_marker_.colors.push_back(this_color);
01801 line_list_marker_.colors.push_back(this_color);
01802
01803
01804 return publishMarker(line_list_marker_);
01805 }
01806
01807 bool RvizVisualTools::publishSpheres(const std::vector<Eigen::Vector3d> &points, const colors &color,
01808 const double scale, const std::string &ns)
01809 {
01810 std::vector<geometry_msgs::Point> points_msg;
01811
01812
01813 for (std::size_t i = 0; i < points.size(); ++i)
01814 {
01815
01816 points_msg.push_back(convertPoint(points[i]));
01817 }
01818
01819 return publishSpheres(points_msg, color, scale, ns);
01820 }
01821
01822 bool RvizVisualTools::publishSpheres(const std::vector<geometry_msgs::Point> &points, const colors &color,
01823 const double scale, const std::string &ns)
01824 {
01825 geometry_msgs::Vector3 scale_vector;
01826 scale_vector.x = scale;
01827 scale_vector.y = scale;
01828 scale_vector.z = scale;
01829 publishSpheres(points, color, scale_vector, ns);
01830 }
01831
01832 bool RvizVisualTools::publishSpheres(const std::vector<geometry_msgs::Point> &points, const colors &color,
01833 const scales &scale, const std::string &ns)
01834 {
01835 publishSpheres(points, color, getScale(scale, false, 0.25), ns);
01836 }
01837
01838 bool RvizVisualTools::publishSpheres(const std::vector<geometry_msgs::Point> &points, const colors &color,
01839 const geometry_msgs::Vector3 &scale, const std::string &ns)
01840 {
01841 spheres_marker_.header.stamp = ros::Time();
01842 spheres_marker_.ns = ns;
01843
01844
01845 spheres_marker_.id++;
01846
01847 std_msgs::ColorRGBA this_color = getColor(color);
01848 spheres_marker_.scale = scale;
01849 spheres_marker_.color = this_color;
01850
01851 spheres_marker_.colors.clear();
01852
01853 spheres_marker_.points = points;
01854
01855
01856 for (std::size_t i = 0; i < points.size(); ++i)
01857 {
01858 spheres_marker_.colors.push_back(this_color);
01859 }
01860
01861
01862 return publishMarker(spheres_marker_);
01863 }
01864
01865 bool RvizVisualTools::publishText(const Eigen::Affine3d &pose, const std::string &text, const colors &color,
01866 const scales &scale, bool static_id)
01867 {
01868 return publishText(convertPose(pose), text, color, getScale(scale), static_id);
01869 }
01870
01871 bool RvizVisualTools::publishText(const Eigen::Affine3d &pose, const std::string &text, const colors &color,
01872 const geometry_msgs::Vector3 scale, bool static_id)
01873 {
01874 return publishText(convertPose(pose), text, color, scale, static_id);
01875 }
01876
01877 bool RvizVisualTools::publishText(const geometry_msgs::Pose &pose, const std::string &text, const colors &color,
01878 const scales &scale, bool static_id)
01879 {
01880 return publishText(pose, text, color, getScale(scale), static_id);
01881 }
01882
01883 bool RvizVisualTools::publishText(const geometry_msgs::Pose &pose, const std::string &text, const colors &color,
01884 const geometry_msgs::Vector3 scale, bool static_id)
01885 {
01886
01887 double temp_id = text_marker_.id;
01888 if (static_id)
01889 {
01890 text_marker_.id = 0;
01891 }
01892 else
01893 {
01894 text_marker_.id++;
01895 }
01896
01897 text_marker_.header.stamp = ros::Time::now();
01898 text_marker_.header.frame_id = base_frame_;
01899 text_marker_.text = text;
01900 text_marker_.pose = pose;
01901 text_marker_.color = getColor(color);
01902 text_marker_.scale = scale;
01903
01904
01905 publishMarker(text_marker_);
01906
01907
01908 if (static_id)
01909 text_marker_.id = temp_id;
01910
01911 return true;
01912 }
01913
01914 bool RvizVisualTools::publishTests()
01915 {
01916
01917 geometry_msgs::Pose pose1;
01918 geometry_msgs::Pose pose2;
01919
01920
01921 ROS_INFO_STREAM_NAMED(name_, "Publising range of colors red->green");
01922 generateRandomPose(pose1);
01923 for (double i = 0; i < 1.0; i += 0.01)
01924 {
01925
01926 geometry_msgs::Vector3 scale = getScale(XLARGE, false, 0.1);
01927 std_msgs::ColorRGBA color = getColorScale(i);
01928 std::size_t id = 1;
01929 publishSphere(pose1, color, scale, "Sphere", id);
01930 ros::Duration(0.1).sleep();
01931
01932 if (!ros::ok())
01933 return false;
01934 }
01935
01936
01937
01938 ROS_INFO_STREAM_NAMED(name_, "Publishing Axis");
01939 generateRandomPose(pose1);
01940 publishAxis(pose1);
01941 ros::Duration(1.0).sleep();
01942
01943 ROS_INFO_STREAM_NAMED(name_, "Publishing Arrow");
01944 generateRandomPose(pose1);
01945 publishArrow(pose1, rviz_visual_tools::RAND);
01946 ros::Duration(1.0).sleep();
01947
01948 ROS_INFO_STREAM_NAMED(name_, "Publishing Sphere");
01949 generateRandomPose(pose1);
01950 publishSphere(pose1, rviz_visual_tools::RAND);
01951 ros::Duration(1.0).sleep();
01952
01953 ROS_INFO_STREAM_NAMED(name_, "Publishing Rectangular Cuboid");
01954
01955 generateRandomPose(pose1);
01956 generateRandomPose(pose2);
01957 publishCuboid(pose1.position, pose2.position, rviz_visual_tools::RAND);
01958 ros::Duration(1.0).sleep();
01959
01960 ROS_INFO_STREAM_NAMED(name_, "Publishing Line");
01961 generateRandomPose(pose1);
01962 generateRandomPose(pose2);
01963 publishLine(pose1.position, pose2.position, rviz_visual_tools::RAND);
01964 ros::Duration(1.0).sleep();
01965
01966
01967
01968
01969
01970
01971
01972 ROS_INFO_STREAM_NAMED(name_, "Publishing Cylinder");
01973 generateRandomPose(pose1);
01974 publishCylinder(pose1, rviz_visual_tools::RAND);
01975 ros::Duration(1.0).sleep();
01976
01977 ROS_INFO_STREAM_NAMED(name_, "Publishing Text");
01978 generateRandomPose(pose1);
01979 publishText(pose1, "Test", rviz_visual_tools::RAND);
01980 ros::Duration(1.0).sleep();
01981
01982 ROS_INFO_STREAM_NAMED(name_, "Publishing Wireframe Cuboid");
01983 Eigen::Vector3d min_point, max_point;
01984
01985 min_point << -0.1, -.25, -.3;
01986 max_point << .3, .2, .1;
01987 generateRandomPose(pose1);
01988 publishWireframeCuboid(convertPose(pose1), min_point, max_point);
01989 ros::Duration(1.0).sleep();
01990
01991 ROS_INFO_STREAM_NAMED(name_, "Publishing depth/width/height Wireframe Cuboid");
01992 double depth = 0.5, width = 0.25, height = 0.125;
01993 generateRandomPose(pose1);
01994 publishWireframeCuboid(convertPose(pose1), depth, width, height);
01995 ros::Duration(1.0).sleep();
01996
01997 ROS_INFO_STREAM_NAMED(name_, "Publishing Planes");
01998 generateRandomPose(pose1);
01999 publishXYPlane(pose1, rviz_visual_tools::RED, 0.1);
02000 ros::Duration(1.0).sleep();
02001 publishXZPlane(pose1, rviz_visual_tools::GREEN, 0.1);
02002 ros::Duration(1.0).sleep();
02003 publishYZPlane(pose1, rviz_visual_tools::BLUE, 0.1);
02004 ros::Duration(1.0).sleep();
02005
02006 ROS_INFO_STREAM_NAMED(name_, "Publising Axis Cone");
02007 generateRandomPose(pose1);
02008 publishCone(pose1, M_PI / 6.0, rviz_visual_tools::RAND, 0.2);
02009 ros::Duration(1.0).sleep();
02010
02011 return true;
02012 }
02013
02014 geometry_msgs::Pose RvizVisualTools::convertPose(const Eigen::Affine3d &pose)
02015 {
02016 tf::poseEigenToMsg(pose, shared_pose_msg_);
02017 return shared_pose_msg_;
02018 }
02019
02020 void RvizVisualTools::convertPoseSafe(const Eigen::Affine3d &pose, geometry_msgs::Pose &pose_msg)
02021 {
02022 tf::poseEigenToMsg(pose, pose_msg);
02023 }
02024
02025 Eigen::Affine3d RvizVisualTools::convertPose(const geometry_msgs::Pose &pose)
02026 {
02027 tf::poseMsgToEigen(pose, shared_pose_eigen_);
02028 return shared_pose_eigen_;
02029 }
02030
02031 Eigen::Affine3d RvizVisualTools::convertPoint32ToPose(const geometry_msgs::Point32 &point)
02032 {
02033 shared_pose_eigen_ = Eigen::Affine3d::Identity();
02034 shared_pose_eigen_.translation().x() = point.x;
02035 shared_pose_eigen_.translation().y() = point.y;
02036 shared_pose_eigen_.translation().z() = point.z;
02037 return shared_pose_eigen_;
02038 }
02039
02040 geometry_msgs::Pose RvizVisualTools::convertPointToPose(const geometry_msgs::Point &point)
02041 {
02042 shared_pose_msg_.orientation.x = 0.0;
02043 shared_pose_msg_.orientation.y = 0.0;
02044 shared_pose_msg_.orientation.z = 0.0;
02045 shared_pose_msg_.orientation.w = 1.0;
02046 shared_pose_msg_.position = point;
02047 return shared_pose_msg_;
02048 }
02049
02050 Eigen::Affine3d RvizVisualTools::convertPointToPose(const Eigen::Vector3d &point)
02051 {
02052 shared_pose_eigen_ = Eigen::Affine3d::Identity();
02053 shared_pose_eigen_.translation() = point;
02054 return shared_pose_eigen_;
02055 }
02056
02057 geometry_msgs::Point RvizVisualTools::convertPoseToPoint(const Eigen::Affine3d &pose)
02058 {
02059 tf::poseEigenToMsg(pose, shared_pose_msg_);
02060 return shared_pose_msg_.position;
02061 }
02062
02063 Eigen::Vector3d RvizVisualTools::convertPoint(const geometry_msgs::Point &point)
02064 {
02065 shared_point_eigen_[0] = point.x;
02066 shared_point_eigen_[1] = point.y;
02067 shared_point_eigen_[2] = point.z;
02068 return shared_point_eigen_;
02069 }
02070
02071 Eigen::Vector3d RvizVisualTools::convertPoint32(const geometry_msgs::Point32 &point)
02072 {
02073 shared_point_eigen_[0] = point.x;
02074 shared_point_eigen_[1] = point.y;
02075 shared_point_eigen_[2] = point.z;
02076 return shared_point_eigen_;
02077 }
02078
02079 geometry_msgs::Point32 RvizVisualTools::convertPoint32(const Eigen::Vector3d &point)
02080 {
02081 shared_point32_msg_.x = point[0];
02082 shared_point32_msg_.y = point[1];
02083 shared_point32_msg_.z = point[2];
02084 return shared_point32_msg_;
02085 }
02086
02087 geometry_msgs::Point RvizVisualTools::convertPoint(const geometry_msgs::Vector3 &point)
02088 {
02089 shared_point_msg_.x = point.x;
02090 shared_point_msg_.y = point.y;
02091 shared_point_msg_.z = point.z;
02092 return shared_point_msg_;
02093 }
02094
02095 geometry_msgs::Point RvizVisualTools::convertPoint(const Eigen::Vector3d &point)
02096 {
02097 shared_point_msg_.x = point.x();
02098 shared_point_msg_.y = point.y();
02099 shared_point_msg_.z = point.z();
02100 return shared_point_msg_;
02101 }
02102
02103 Eigen::Affine3d RvizVisualTools::convertFromXYZRPY(std::vector<double> transform6)
02104 {
02105 if (transform6.size() != 6)
02106 {
02107
02108 ROS_ERROR_STREAM_NAMED("visual_tools", "Incorrect number of variables passed for 6-size transform");
02109 throw;
02110 }
02111
02112 return convertFromXYZRPY(transform6[0], transform6[1], transform6[2], transform6[3], transform6[4], transform6[5]);
02113 }
02114
02115 Eigen::Affine3d RvizVisualTools::convertFromXYZRPY(const double &x, const double &y, const double &z,
02116 const double &roll, const double &pitch, const double &yaw)
02117 {
02118
02119 Eigen::AngleAxisd roll_angle(roll, Eigen::Vector3d::UnitX());
02120 Eigen::AngleAxisd pitch_angle(pitch, Eigen::Vector3d::UnitY());
02121 Eigen::AngleAxisd yaw_angle(yaw, Eigen::Vector3d::UnitZ());
02122 Eigen::Quaternion<double> quaternion = roll_angle * pitch_angle * yaw_angle;
02123
02124 return Eigen::Translation3d(x, y, z) * quaternion;
02125 }
02126
02127 void RvizVisualTools::convertToXYZRPY(const Eigen::Affine3d &pose, std::vector<double> &xyzrpy)
02128 {
02129 xyzrpy.resize(6);
02130 convertToXYZRPY(pose, xyzrpy[0], xyzrpy[1], xyzrpy[2], xyzrpy[3], xyzrpy[4], xyzrpy[5]);
02131 }
02132
02133 void RvizVisualTools::convertToXYZRPY(const Eigen::Affine3d &pose, double &x, double &y, double &z, double &roll,
02134 double &pitch, double &yaw)
02135 {
02136 x = pose(0, 3);
02137 y = pose(1, 3);
02138 z = pose(2, 3);
02139
02140
02141 Eigen::Vector3d vec = pose.rotation().eulerAngles(0, 1, 2);
02142 roll = vec[0];
02143 pitch = vec[1];
02144 yaw = vec[2];
02145 }
02146
02147 void RvizVisualTools::generateRandomPose(geometry_msgs::Pose &pose, RandomPoseBounds pose_bounds)
02148 {
02149 generateRandomPose(shared_pose_eigen_, pose_bounds);
02150 pose = convertPose(shared_pose_eigen_);
02151 }
02152
02153 void RvizVisualTools::generateRandomCuboid(geometry_msgs::Pose &cuboid_pose, double &depth, double &width,
02154 double &height, RandomPoseBounds pose_bounds,
02155 RandomCuboidBounds cuboid_bounds)
02156 {
02157
02158 depth = fRand(cuboid_bounds.cuboid_size_min_, cuboid_bounds.cuboid_size_max_);
02159 width = fRand(cuboid_bounds.cuboid_size_min_, cuboid_bounds.cuboid_size_max_);
02160 height = fRand(cuboid_bounds.cuboid_size_min_, cuboid_bounds.cuboid_size_max_);
02161
02162
02163 generateRandomPose(cuboid_pose, pose_bounds);
02164 }
02165
02166 void RvizVisualTools::generateRandomPose(Eigen::Affine3d &pose, RandomPoseBounds pose_bounds)
02167 {
02168
02169
02170
02171 if (pose_bounds.elevation_min_ < 0)
02172 {
02173 ROS_WARN_STREAM_NAMED(name_, "min elevation bound < 0, setting equal to 0");
02174 pose_bounds.elevation_min_ = 0;
02175 }
02176
02177 if (pose_bounds.elevation_max_ > M_PI)
02178 {
02179 ROS_WARN_STREAM_NAMED(name_, "max elevation bound > pi, setting equal to pi ");
02180 pose_bounds.elevation_max_ = M_PI;
02181 }
02182
02183 if (pose_bounds.azimuth_min_ < 0)
02184 {
02185 ROS_WARN_STREAM_NAMED(name_, "min azimuth bound < 0, setting equal to 0");
02186 pose_bounds.azimuth_min_ = 0;
02187 }
02188
02189 if (pose_bounds.azimuth_max_ > 2 * M_PI)
02190 {
02191 ROS_WARN_STREAM_NAMED(name_, "max azimuth bound > 2 pi, setting equal to 2 pi ");
02192 pose_bounds.azimuth_max_ = 2 * M_PI;
02193 }
02194
02195
02196 pose.translation().x() = dRand(pose_bounds.x_min_, pose_bounds.x_max_);
02197 pose.translation().y() = dRand(pose_bounds.y_min_, pose_bounds.y_max_);
02198 pose.translation().z() = dRand(pose_bounds.z_min_, pose_bounds.z_max_);
02199
02200
02201 double angle = dRand(pose_bounds.angle_min_, pose_bounds.angle_max_);
02202 double elevation = dRand(pose_bounds.elevation_min_, pose_bounds.elevation_max_);
02203 double azimuth = dRand(pose_bounds.azimuth_min_, pose_bounds.azimuth_max_);
02204
02205 Eigen::Vector3d axis;
02206 axis[0] = sin(elevation) * cos(azimuth);
02207 axis[1] = sin(elevation) * sin(azimuth);
02208 axis[2] = cos(elevation);
02209
02210 Eigen::Quaterniond quaternion(Eigen::AngleAxis<double>(static_cast<double>(angle), axis));
02211 pose = Eigen::Translation3d(pose.translation().x(), pose.translation().y(), pose.translation().z()) * quaternion;
02212 }
02213
02214 void RvizVisualTools::generateEmptyPose(geometry_msgs::Pose &pose)
02215 {
02216
02217 pose.position.x = 0;
02218 pose.position.y = 0;
02219 pose.position.z = 0;
02220
02221
02222 pose.orientation.x = 0;
02223 pose.orientation.y = 0;
02224 pose.orientation.z = 0;
02225 pose.orientation.w = 1;
02226 }
02227
02228 bool RvizVisualTools::posesEqual(const Eigen::Affine3d &pose1, const Eigen::Affine3d &pose2, const double& threshold)
02229 {
02230 static const std::size_t NUM_VARS = 16;
02231
02232 for (std::size_t i = 0; i < NUM_VARS; ++i)
02233 {
02234 if (fabs(pose1.data()[i] - pose2.data()[i]) > threshold)
02235 {
02236 return false;
02237 }
02238 }
02239
02240 return true;
02241 }
02242
02243 double RvizVisualTools::dRand(double dMin, double dMax)
02244 {
02245 double d = static_cast<double>(rand()) / RAND_MAX;
02246 return dMin + d * (dMax - dMin);
02247 }
02248
02249 float RvizVisualTools::fRand(float dMin, float dMax)
02250 {
02251 float d = static_cast<float>(rand()) / RAND_MAX;
02252 return dMin + d * (dMax - dMin);
02253 }
02254
02255 int RvizVisualTools::iRand(int min, int max)
02256 {
02257 int n = max - min + 1;
02258 int remainder = RAND_MAX % n;
02259 int x;
02260 do
02261 {
02262 x = rand();
02263 } while (x >= RAND_MAX - remainder);
02264 return min + x % n;
02265 }
02266
02267 void RvizVisualTools::enableInternalBatchPublishing(bool enable)
02268 {
02269
02270 if (batch_publishing_enabled_)
02271 {
02272 return;
02273 }
02274 internal_batch_publishing_enabled_ = true;
02275 }
02276
02277 bool RvizVisualTools::triggerInternalBatchPublishAndDisable()
02278 {
02279 internal_batch_publishing_enabled_ = false;
02280
02281 bool result = publishMarkers(markers_);
02282
02283 markers_.markers.clear();
02284 return result;
02285 }
02286
02287 void RvizVisualTools::printTransform(const Eigen::Affine3d &transform)
02288 {
02289 Eigen::Quaterniond q(transform.rotation());
02290 std::cout << "T.xyz = [" << transform.translation().x() << ", " << transform.translation().y() << ", "
02291 << transform.translation().z() << "], Q.xyzw = [" << q.x() << ", " << q.y() << ", " << q.z() << ", "
02292 << q.w() << "]" << std::endl;
02293 }
02294
02295 void RvizVisualTools::printTransformRPY(const Eigen::Affine3d &transform)
02296 {
02297 double x, y, z, r, p, yaw;
02298 convertToXYZRPY(transform, x, y, z, r, p, yaw);
02299 std::cout << "transform: [" << x << ", " << y << ", " << z << ", " << r << ", " << p << ", " << yaw << "]\n";
02300 }
02301
02302 }