61 : nh_(nh), marker_topic_(
std::move(marker_topic)), base_frame_(
std::move(base_frame))
214 mesh_marker_.type = visualization_msgs::Marker::MESH_RESOURCE;
249 text_marker_.type = visualization_msgs::Marker::TEXT_VIEW_FACING;
278 if (wait_for_subscriber)
286 bool blocking =
true;
292 bool blocking =
false;
313 if (blocking && num_existing_subscribers == 0)
319 while (num_existing_subscribers == 0)
324 << wait_time <<
" sec. It is possible initially published visual messages " 369 std_msgs::ColorRGBA result;
486 "be used with getColor(). Defaulting to " 505 case 0:
return BLACK;
break;
506 case 1:
return BROWN;
break;
507 case 2:
return BLUE;
break;
508 case 3:
return CYAN;
break;
509 case 4:
return GREY;
break;
511 case 6:
return GREEN;
break;
514 case 9:
return ORANGE;
break;
515 case 10:
return PURPLE;
break;
516 case 11:
return RED;
break;
517 case 12:
return PINK;
break;
518 case 13:
return WHITE;
break;
519 case 14:
return YELLOW;
break;
523 case 18:
return RAND;
break;
524 case 19:
return CLEAR;
break;
525 case 20:
return DEFAULT;
break;
539 case 4:
return XSMALL;
break;
540 case 5:
return SMALL;
break;
541 case 6:
return MEDIUM;
break;
542 case 7:
return LARGE;
break;
543 case 8:
return XLARGE;
break;
547 default:
throw std::runtime_error(
"Unknown size");
558 case XXXXSMALL:
return "XXXXSMALL";
break;
559 case XXXSMALL:
return "XXXSMALL";
break;
560 case XXSMALL:
return "XXSMALL";
break;
561 case XSMALL:
return "XSMALL";
break;
562 case SMALL:
return "SMALL";
break;
563 case MEDIUM:
return "MEDIUM";
break;
564 case LARGE:
return "LARGE";
break;
565 case XLARGE:
return "XLARGE";
break;
566 case XXLARGE:
return "XXLARGE";
break;
567 case XXXLARGE:
return "XXXLARGE";
break;
568 case XXXXLARGE:
return "XXXXLARGE";
break;
569 default:
throw std::runtime_error(
"Unknown size");
577 std_msgs::ColorRGBA result;
579 const std::size_t MAX_ATTEMPTS = 20;
580 std::size_t attempts = 0;
585 result.r =
fRand(0.0, 1.0);
586 result.g =
fRand(0.0, 1.0);
587 result.b =
fRand(0.0, 1.0);
591 if (attempts > MAX_ATTEMPTS)
596 }
while (result.r + result.g + result.b < 1.5);
606 return start + (((end - start) / range) * value);
623 std_msgs::ColorRGBA start;
624 std_msgs::ColorRGBA end;
631 else if (value == 1.0)
635 else if (value <= 0.5)
644 value = fmod(value, 0.5);
647 std_msgs::ColorRGBA result;
648 result.r =
slerp(start.r, end.r, 0.5, value);
649 result.g =
slerp(start.g, end.g, 0.5, value);
650 result.b =
slerp(start.b, end.b, 0.5, value);
664 geometry_msgs::Vector3 result;
716 Eigen::Vector3d center;
717 center[0] = (a[0] + b[0]) / 2.0;
718 center[1] = (a[1] + b[1]) / 2.0;
719 center[2] = (a[2] + b[2]) / 2.0;
725 bool verbose =
false;
734 Eigen::Affine3d result_pose = Eigen::Affine3d::Identity();
737 Eigen::Quaterniond q;
738 Eigen::Vector3d axis_vector = b - a;
742 std::cout << std::endl;
743 std::cout <<
"axis_vector " << std::endl;
747 axis_vector.normalize();
751 std::cout << std::endl;
752 std::cout <<
"axis_vector after normalize " << std::endl;
756 Eigen::Vector3d up_vector(0.0, 0.0, 1.0);
757 Eigen::Vector3d right_axis_vector = axis_vector.cross(up_vector);
761 std::cout <<
"right_axis_vector " << std::endl;
765 if (right_axis_vector[0] == 0.0 && right_axis_vector[1] == 0.0 && right_axis_vector[2] == 0.0)
769 std::cout <<
"right axis vector is zero " << std::endl;
771 result_pose = Eigen::AngleAxisd(-0.5 * M_PI, Eigen::Vector3d::UnitY());
772 result_pose.translation() = a;
776 right_axis_vector.normalized();
780 std::cout <<
"right_axis_vector normalized " << std::endl;
784 double theta = axis_vector.dot(up_vector);
785 double angle_rotation = -1.0 *
acos(theta);
805 std::cout <<
"rotation matrix: " << std::endl;
806 std::cout << q.toRotationMatrix() << std::endl;
819 std::cout <<
"rotation matrix after normalize: " << std::endl;
820 std::cout << q.toRotationMatrix() << std::endl;
824 result_pose = q * Eigen::AngleAxisd(-0.5 * M_PI, Eigen::Vector3d::UnitY());
825 result_pose.translation() = a;
857 if (
markers_.markers.size() >= queueSize || queueSize == 0)
907 if (markers.markers.empty())
915 for (
auto& marker : markers.markers)
917 marker.color.r = 1.0 - marker.color.r;
918 marker.color.g = 1.0 - marker.color.g;
919 marker.color.b = 1.0 - marker.color.b;
920 for (
auto& color : marker.colors)
922 color.r = 1.0 - color.r;
923 color.g = 1.0 - color.g;
924 color.b = 1.0 - color.b;
948 geometry_msgs::Point p[3];
949 static const double delta_theta = M_PI / 16.0;
953 for (std::size_t i = 0; i < 32; i++)
960 p[1].y = scale *
cos(theta) / angle;
961 p[1].z = scale *
sin(theta) / angle;
964 p[2].y = scale *
cos(theta + delta_theta) / angle;
965 p[2].z = scale *
sin(theta + delta_theta) / angle;
971 theta += delta_theta;
994 geometry_msgs::Point p[4];
995 p[0].x = 1.0 * scale;
996 p[0].y = 1.0 * scale;
999 p[1].x = -1.0 * scale;
1000 p[1].y = 1.0 * scale;
1003 p[2].x = -1.0 * scale;
1004 p[2].y = -1.0 * scale;
1007 p[3].x = 1.0 * scale;
1008 p[3].y = -1.0 * scale;
1040 geometry_msgs::Point p[4];
1041 p[0].x = 1.0 * scale;
1043 p[0].z = 1.0 * scale;
1045 p[1].x = -1.0 * scale;
1047 p[1].z = 1.0 * scale;
1049 p[2].x = -1.0 * scale;
1051 p[2].z = -1.0 * scale;
1053 p[3].x = 1.0 * scale;
1055 p[3].z = -1.0 * scale;
1086 geometry_msgs::Point p[4];
1088 p[0].y = 1.0 * scale;
1089 p[0].z = 1.0 * scale;
1092 p[1].y = -1.0 * scale;
1093 p[1].z = 1.0 * scale;
1096 p[2].y = -1.0 * scale;
1097 p[2].z = -1.0 * scale;
1100 p[3].y = 1.0 * scale;
1101 p[3].z = -1.0 * scale;
1128 geometry_msgs::Pose pose_msg;
1136 geometry_msgs::Pose pose_msg;
1142 const std::string& ns, std::size_t
id)
1144 geometry_msgs::Pose pose_msg;
1145 pose_msg.position = point;
1158 geometry_msgs::Vector3 scale_msg;
1166 const std::string& ns, std::size_t
id)
1172 const geometry_msgs::Vector3 scale,
const std::string& ns, std::size_t
id)
1178 const geometry_msgs::Vector3 scale,
const std::string& ns, std::size_t
id)
1180 geometry_msgs::Pose pose_msg;
1186 const geometry_msgs::Vector3 scale,
const std::string& ns, std::size_t
id)
1211 const geometry_msgs::Vector3 scale,
const std::string& ns, std::size_t
id)
1254 Eigen::Affine3d arrow_pose = pose * Eigen::AngleAxisd(M_PI / 2, Eigen::Vector3d::UnitZ());
1260 Eigen::Affine3d arrow_pose =
convertPose(pose) * Eigen::AngleAxisd(M_PI / 2, Eigen::Vector3d::UnitZ());
1266 Eigen::Affine3d arrow_pose =
convertPose(pose.pose) * Eigen::AngleAxisd(M_PI / 2, Eigen::Vector3d::UnitZ());
1267 geometry_msgs::PoseStamped new_pose = pose;
1275 Eigen::Affine3d arrow_pose = pose * Eigen::AngleAxisd(-M_PI / 2, Eigen::Vector3d::UnitY());
1281 Eigen::Affine3d arrow_pose =
convertPose(pose) * Eigen::AngleAxisd(-M_PI / 2, Eigen::Vector3d::UnitY());
1287 Eigen::Affine3d arrow_pose =
convertPose(pose.pose) * Eigen::AngleAxisd(-M_PI / 2, Eigen::Vector3d::UnitY());
1288 geometry_msgs::PoseStamped new_pose = pose;
1296 Eigen::Affine3d arrow_pose =
convertPose(pose.pose) * Eigen::AngleAxisd(-M_PI / 2, Eigen::Vector3d::UnitY());
1297 geometry_msgs::PoseStamped new_pose = pose;
1299 return publishArrow(new_pose, color, scale, length,
id);
1379 scales scale, std::size_t
id)
1423 geometry_msgs::Pose pose_shifted = pose;
1424 pose_shifted.position.x -= 0.05;
1425 pose_shifted.position.y -= 0.05;
1426 pose_shifted.position.z -= 0.05;
1427 publishText(pose_shifted, label, color, static_cast<scales>(static_cast<int>(scale) + 1),
false);
1434 return publishAxis(pose, radius * 10.0, radius, ns);
1440 return publishAxis(pose, radius * 10.0, radius, ns);
1458 const std::string& ns)
1461 Eigen::Affine3d x_pose =
1462 Eigen::Translation3d(length / 2.0, 0, 0) * Eigen::AngleAxisd(M_PI / 2.0, Eigen::Vector3d::UnitY());
1463 x_pose = pose * x_pose;
1467 Eigen::Affine3d y_pose =
1468 Eigen::Translation3d(0, length / 2.0, 0) * Eigen::AngleAxisd(M_PI / 2.0, Eigen::Vector3d::UnitX());
1469 y_pose = pose * y_pose;
1473 Eigen::Affine3d z_pose = Eigen::Translation3d(0, 0, length / 2.0) * Eigen::AngleAxisd(0, Eigen::Vector3d::UnitZ());
1474 z_pose = pose * z_pose;
1483 for (
const auto& i : path)
1493 const std::string& ns)
1496 for (
const auto& i : path)
1505 scales scale,
const std::string& ns)
1512 double radius,
const std::string& ns)
1518 const std_msgs::ColorRGBA& color,
double radius,
const std::string& ns)
1521 double height = (point1 - point2).lpNorm<2>();
1527 Eigen::Affine3d pose;
1531 Eigen::Affine3d rotation;
1532 rotation = Eigen::AngleAxisd(0.5 * M_PI, Eigen::Vector3d::UnitY());
1533 pose = pose * rotation;
1540 const std::string& ns)
1546 const std::string& ns)
1552 double radius,
const std::string& ns)
1575 const std::string& ns, std::size_t
id)
1581 double scale,
const std::string& ns, std::size_t
id)
1622 typedef std::pair<std::size_t, std::size_t> node_ids;
1623 std::set<node_ids> added_edges;
1624 std::pair<std::set<node_ids>::iterator,
bool> return_value;
1625 Eigen::Vector3d a, b;
1626 for (std::size_t i = 0; i < graph.nodes.size(); ++i)
1628 for (std::size_t j = 0; j < graph.edges[i].node_ids.size(); ++j)
1631 return_value = added_edges.insert(node_ids(i, j));
1632 if (!return_value.second)
1640 b =
convertPoint(graph.nodes[graph.edges[i].node_ids[j]]);
1656 colors color,
const std::string& ns, std::size_t
id)
1674 geometry_msgs::Pose pose;
1675 pose.position.x = (point1.x - point2.x) / 2.0 + point2.x;
1676 pose.position.y = (point1.y - point2.y) / 2.0 + point2.y;
1677 pose.position.z = (point1.z - point2.z) / 2.0 + point2.z;
1764 geometry_msgs::Vector3 scale;
1772 const std_msgs::ColorRGBA& color,
scales scale)
1778 const std_msgs::ColorRGBA& color,
double radius)
1780 geometry_msgs::Vector3 scale;
1794 const std_msgs::ColorRGBA& color,
scales scale)
1800 const std_msgs::ColorRGBA& color,
const geometry_msgs::Vector3& scale)
1820 BOOST_ASSERT_MSG(aPoints.size() == bPoints.size() && bPoints.size() == colors.size(),
"Mismatching vector sizes: " 1821 "aPoints, bPoints, and colors");
1823 std::vector<geometry_msgs::Point> aPoints_msg;
1824 std::vector<geometry_msgs::Point> bPoints_msg;
1825 std::vector<std_msgs::ColorRGBA> colors_msg;
1827 for (std::size_t i = 0; i < aPoints.size(); ++i)
1833 colors_msg.push_back(
getColor(colors[i]));
1835 BOOST_ASSERT_MSG(aPoints_msg.size() == bPoints_msg.size() && bPoints_msg.size() == colors_msg.size(),
"Mismatched " 1842 const std::vector<geometry_msgs::Point>& bPoints,
1843 const std::vector<std_msgs::ColorRGBA>&
colors,
const geometry_msgs::Vector3& scale)
1858 for (std::size_t i = 0; i < aPoints.size(); ++i)
1868 BOOST_ASSERT_MSG(
line_list_marker_.colors.size() == aPoints.size() * 2,
"Colors arrays mismatch in size");
1875 const std::string& ns)
1877 if (path.size() < 2)
1889 std_msgs::ColorRGBA this_color =
getColor(color);
1895 for (std::size_t i = 1; i < path.size(); ++i)
1909 const std::string& ns)
1911 std::vector<geometry_msgs::Point> point_path(path.size());
1912 for (std::size_t i = 0; i < path.size(); ++i)
1914 point_path[i] = path[i].position;
1921 const std::string& ns)
1927 const std::string& ns)
1933 const std::string& ns)
1939 const std::string& ns)
1941 if (path.size() < 2)
1948 for (std::size_t i = 1; i < path.size(); ++i)
1957 const std::string& ns)
1959 if (path.size() < 2)
1966 for (std::size_t i = 1; i < path.size(); ++i)
1975 const std::string& ns)
1977 if (path.size() < 2)
1984 for (std::size_t i = 1; i < path.size(); ++i)
1986 publishCylinder(path[i - 1].translation(), path[i].translation(), color, radius, ns);
1993 double radius,
const std::string& ns)
1995 if (path.size() < 2)
2001 if (path.size() != colors.size())
2009 for (std::size_t i = 1; i < path.size(); ++i)
2018 double radius,
const std::string& ns)
2020 if (path.size() < 2)
2026 if (path.size() != colors.size())
2034 for (std::size_t i = 1; i < path.size(); ++i)
2043 const std::string& ns)
2045 std::vector<geometry_msgs::Point> points;
2046 geometry_msgs::Point temp;
2047 geometry_msgs::Point first;
2050 for (std::size_t i = 0; i < polygon.points.size(); ++i)
2052 temp.x = polygon.points[i].x;
2053 temp.y = polygon.points[i].y;
2054 temp.z = polygon.points[i].z;
2059 points.push_back(temp);
2061 points.push_back(first);
2067 colors color,
const std::string& ns, std::size_t
id)
2069 Eigen::Vector3d min_point, max_point;
2070 min_point << -depth / 2, -width / 2, -height / 2;
2071 max_point << depth / 2, width / 2, height / 2;
2076 const Eigen::Vector3d& max_point,
colors color,
const std::string& ns,
2080 Eigen::Vector3d p1(min_point[0], min_point[1], min_point[2]);
2081 Eigen::Vector3d p2(min_point[0], min_point[1], max_point[2]);
2082 Eigen::Vector3d p3(max_point[0], min_point[1], max_point[2]);
2083 Eigen::Vector3d p4(max_point[0], min_point[1], min_point[2]);
2084 Eigen::Vector3d p5(min_point[0], max_point[1], min_point[2]);
2085 Eigen::Vector3d p6(min_point[0], max_point[1], max_point[2]);
2086 Eigen::Vector3d p7(max_point[0], max_point[1], max_point[2]);
2087 Eigen::Vector3d p8(max_point[0], max_point[1], min_point[2]);
2111 std_msgs::ColorRGBA this_color =
getColor(color);
2183 scales scale, std::size_t
id)
2195 Eigen::Vector3d p1(-width / 2.0, -height / 2.0, 0.0);
2196 Eigen::Vector3d p2(-width / 2.0, height / 2.0, 0.0);
2197 Eigen::Vector3d p3(width / 2.0, height / 2.0, 0.0);
2198 Eigen::Vector3d p4(width / 2.0, -height / 2.0, 0.0);
2209 std_msgs::ColorRGBA this_color =
getColor(color);
2241 const Eigen::Vector3d& p2_in,
const Eigen::Vector3d& p3_in,
2242 const Eigen::Vector3d& p4_in,
colors color,
scales scale)
2262 std_msgs::ColorRGBA this_color =
getColor(color);
2294 const std::string& ns)
2296 std::vector<geometry_msgs::Point> points_msg;
2298 for (
const auto& point : points)
2307 const std::string& ns)
2309 std::vector<geometry_msgs::Point> points_msg;
2311 for (
const auto& point : points)
2320 const std::string& ns)
2322 geometry_msgs::Vector3 scale_vector;
2330 const std::string& ns)
2336 const geometry_msgs::Vector3& scale,
const std::string& ns)
2344 std_msgs::ColorRGBA this_color =
getColor(color);
2352 for (std::size_t i = 0; i < points.size(); ++i)
2362 scales scale,
const std::string& ns)
2364 BOOST_ASSERT_MSG(points.size() == colors.size(),
"Mismatching vector sizes: points and colors");
2366 std::vector<geometry_msgs::Point> points_msg;
2367 std::vector<std_msgs::ColorRGBA> colors_msg;
2369 for (std::size_t i = 0; i < points.size(); ++i)
2374 colors_msg.push_back(
getColor(colors[i]));
2381 const std::vector<std_msgs::ColorRGBA>&
colors,
2382 const geometry_msgs::Vector3& scale,
const std::string& ns)
2405 const geometry_msgs::Vector3 scale,
bool static_id)
2417 const geometry_msgs::Vector3 scale,
bool static_id)
2451 geometry_msgs::Pose pose_msg;
2463 Eigen::Affine3d shared_pose_eigen_;
2465 return shared_pose_eigen_;
2475 Eigen::Affine3d shared_pose_eigen_;
2476 shared_pose_eigen_ = Eigen::Affine3d::Identity();
2477 shared_pose_eigen_.translation().x() = point.x;
2478 shared_pose_eigen_.translation().y() = point.y;
2479 shared_pose_eigen_.translation().z() = point.z;
2480 return shared_pose_eigen_;
2485 geometry_msgs::Pose pose_msg;
2486 pose_msg.orientation.x = 0.0;
2487 pose_msg.orientation.y = 0.0;
2488 pose_msg.orientation.z = 0.0;
2489 pose_msg.orientation.w = 1.0;
2490 pose_msg.position = point;
2496 Eigen::Affine3d shared_pose_eigen_;
2497 shared_pose_eigen_ = Eigen::Affine3d::Identity();
2498 shared_pose_eigen_.translation() = point;
2499 return shared_pose_eigen_;
2504 geometry_msgs::Pose pose_msg;
2506 return pose_msg.position;
2511 Eigen::Vector3d point_eigen;
2512 point_eigen[0] = point.x;
2513 point_eigen[1] = point.y;
2514 point_eigen[2] = point.z;
2520 Eigen::Vector3d point_eigen;
2521 point_eigen[0] = point.x;
2522 point_eigen[1] = point.y;
2523 point_eigen[2] = point.z;
2529 geometry_msgs::Point32 point32_msg;
2530 point32_msg.x = point[0];
2531 point32_msg.y = point[1];
2532 point32_msg.z = point[2];
2538 geometry_msgs::Point point_msg;
2539 point_msg.x = point.x;
2540 point_msg.y = point.y;
2541 point_msg.z = point.z;
2547 geometry_msgs::Point point_msg;
2548 point_msg.x = point.x();
2549 point_msg.y = point.y();
2550 point_msg.z = point.z();
2562 Eigen::AngleAxisd roll_angle(roll, Eigen::Vector3d::UnitX());
2563 Eigen::AngleAxisd pitch_angle(pitch, Eigen::Vector3d::UnitY());
2564 Eigen::AngleAxisd yaw_angle(yaw, Eigen::Vector3d::UnitZ());
2565 Eigen::Quaternion<double> quaternion = roll_angle * pitch_angle * yaw_angle;
2567 return Eigen::Translation3d(x, y, z) * quaternion;
2573 Eigen::Affine3d result;
2578 result = Eigen::Translation3d(tx, ty, tz) * Eigen::AngleAxisd(rx, Eigen::Vector3d::UnitX()) *
2579 Eigen::AngleAxisd(ry, Eigen::Vector3d::UnitY()) * Eigen::AngleAxisd(rz, Eigen::Vector3d::UnitZ());
2583 result = Eigen::Translation3d(tx, ty, tz) * Eigen::AngleAxisd(rz, Eigen::Vector3d::UnitZ()) *
2584 Eigen::AngleAxisd(ry, Eigen::Vector3d::UnitY()) * Eigen::AngleAxisd(rx, Eigen::Vector3d::UnitX());
2588 result = Eigen::Translation3d(tx, ty, tz) * Eigen::AngleAxisd(rz, Eigen::Vector3d::UnitZ()) *
2589 Eigen::AngleAxisd(rx, Eigen::Vector3d::UnitX()) * Eigen::AngleAxisd(rz, Eigen::Vector3d::UnitZ());
2602 if (transform6.size() != 6)
2608 return convertFromXYZRPY(transform6[0], transform6[1], transform6[2], transform6[3], transform6[4], transform6[5],
2615 convertToXYZRPY(pose, xyzrpy[0], xyzrpy[1], xyzrpy[2], xyzrpy[3], xyzrpy[4], xyzrpy[5]);
2619 double& pitch,
double& yaw)
2626 Eigen::Vector3d vec = pose.rotation().eulerAngles(0, 1, 2);
2634 Eigen::Affine3d pose_eigen;
2691 Eigen::Vector3d axis;
2692 axis[0] =
sin(elevation) *
cos(azimuth);
2693 axis[1] =
sin(elevation) *
sin(azimuth);
2694 axis[2] =
cos(elevation);
2696 Eigen::Quaterniond quaternion(Eigen::AngleAxis<double>(static_cast<double>(angle), axis));
2697 pose = Eigen::Translation3d(pose.translation().x(), pose.translation().y(), pose.translation().z()) * quaternion;
2703 pose.position.x = 0;
2704 pose.position.y = 0;
2705 pose.position.z = 0;
2708 pose.orientation.x = 0;
2709 pose.orientation.y = 0;
2710 pose.orientation.z = 0;
2711 pose.orientation.w = 1;
2716 static const std::size_t NUM_VARS = 16;
2718 for (std::size_t i = 0; i < NUM_VARS; ++i)
2720 if (fabs(pose1.data()[i] - pose2.data()[i]) > threshold)
2731 double d =
static_cast<double>(rand()) / RAND_MAX;
2732 return min + d * (max - min);
2737 float d =
static_cast<float>(rand()) / RAND_MAX;
2738 return min + d * (max - min);
2743 int n = max - min + 1;
2744 int remainder = RAND_MAX % n;
2749 }
while (x >= RAND_MAX - remainder);
2755 std::cout <<
"T.xyz = [" << translation.x() <<
", " << translation.y() <<
", " << translation.z() <<
"]" << std::endl;
2760 Eigen::Quaterniond q(transform.rotation());
2761 std::cout <<
"T.xyz = [" << transform.translation().x() <<
", " << transform.translation().y() <<
", " 2762 << transform.translation().z() <<
"], Q.xyzw = [" << q.x() <<
", " << q.y() <<
", " << q.z() <<
", " 2763 << q.w() <<
"]" << std::endl;
2769 Eigen::Vector3d vec = transform.rotation().eulerAngles(0, 1, 2);
2770 std::cout <<
"transform: [" << transform.translation().x() <<
", " << transform.translation().y() <<
", " 2771 << transform.translation().z() <<
", " << vec[0] <<
", " << vec[1] <<
", " << vec[2] <<
"]\n";
2776 std::cout <<
"T.xyz = [" << transform.translation().x() <<
", " << transform.translation().y() <<
", " 2777 << transform.translation().z() <<
"], R = \n" 2778 << transform.rotation() <<
"\n";
#define ROS_DEBUG_STREAM_NAMED(name, args)
void publish(const boost::shared_ptr< M > &message) const
#define ROS_ERROR_STREAM_NAMED(name, args)
std::vector< Eigen::Affine3d, Eigen::aligned_allocator< Eigen::Affine3d > > vector_Affine3d
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > vector_Vector3d
void poseEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Pose &m)
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
#define ROS_INFO_STREAM_NAMED(name, args)
void vectorEigenToTF(const Eigen::Vector3d &e, tf::Vector3 &t)
#define ROS_WARN_STREAM_ONCE_NAMED(name, args)
TFSIMD_FORCE_INLINE const tfScalar & x() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void pointEigenToMsg(const Eigen::Vector3d &e, geometry_msgs::Point &m)
void quaternionTFToEigen(const tf::Quaternion &t, Eigen::Quaterniond &e)
uint32_t getNumSubscribers() const
INLINE Rall1d< T, V, S > acos(const Rall1d< T, V, S > &x)
std::string getTopic() const
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
#define ROS_ERROR_STREAM(args)
ROSCPP_DECL void spinOnce()
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
#define ROS_WARN_STREAM_NAMED(name, args)