22 #include <visualization_msgs/MarkerArray.h>
24 int main(
int argc,
char** argv)
29 std::cerr << std::endl;
30 std::cerr <<
"usage:" << std::endl;
31 std::cerr <<
" viz_mesh link_name" << std::endl;
32 std::cerr << std::endl;
35 std::string link_name = argv[1];
38 ros::init(argc, argv,
"robot_calibration_mesh_viz");
59 std::string root_name = model.getRoot()->name;
73 visualization_msgs::MarkerArray markers;
74 for (
size_t t = 0;
t < mesh->triangle_count; ++
t)
77 visualization_msgs::Marker msg;
78 msg.header.frame_id = link_name;
82 msg.type = msg.LINE_STRIP;
83 msg.pose.orientation.w = 1.0;
92 int v1_idx = mesh->triangles[(3 *
t) + 0];
93 int v2_idx = mesh->triangles[(3 *
t) + 1];
94 int v3_idx = mesh->triangles[(3 *
t) + 2];
95 geometry_msgs::Point v1;
96 v1.x = mesh->vertices[(3 * v1_idx) + 0];
97 v1.y = mesh->vertices[(3 * v1_idx) + 1];
98 v1.z = mesh->vertices[(3 * v1_idx) + 2];
99 geometry_msgs::Point v2;
100 v2.x = mesh->vertices[(3 * v2_idx) + 0];
101 v2.y = mesh->vertices[(3 * v2_idx) + 1];
102 v2.z = mesh->vertices[(3 * v2_idx) + 2];
103 geometry_msgs::Point v3;
104 v3.x = mesh->vertices[(3 * v3_idx) + 0];
105 v3.y = mesh->vertices[(3 * v3_idx) + 1];
106 v3.z = mesh->vertices[(3 * v3_idx) + 2];
108 msg.points.push_back(v1);
109 msg.points.push_back(v2);
110 msg.points.push_back(v3);
111 msg.points.push_back(v1);
113 markers.markers.push_back(msg);