13 marker_array.markers.resize(list.size());
15 for (std::size_t i = 0; i < list.size(); i++)
18 visualization_msgs::Marker marker;
19 marker.header.frame_id = frame;
23 marker.ns =
"cylinders_ns";
30 marker.type = visualization_msgs::Marker::CYLINDER;
31 marker.action = visualization_msgs::Marker::ADD;
34 marker.pose.position.x = list[i].getCentroid()(0);
35 marker.pose.position.y = list[i].getCentroid()(1);
36 marker.pose.position.z = list[i].getCentroid()(2);
39 geometry_msgs::PoseStamped cylinder_pose_msg;
40 Eigen::Vector3d axis = list[i].getCurvatureAxis();
41 Eigen::Vector3d normal = list[i].getNormal();
42 Eigen::Vector3d perp = normal.cross(axis);
43 tf::Matrix3x3 rotation_matrix(perp(0), normal(0), axis(0), perp(1), normal(1), axis(1), perp(2), normal(2),
49 marker.pose.orientation = cylinder_pose_msg.pose.orientation;
52 marker.scale.x = list[i].getRadius() * 2;
53 marker.scale.y = list[i].getRadius() * 2;
54 marker.scale.z = list[i].getExtent();
62 marker_array.markers[i] = marker;
69 const std::string &frame)
73 marker_array.markers.resize(handles.size() * 2);
75 for (std::size_t i = 0; i < handles.size() * 2; i++)
77 visualization_msgs::Marker marker;
78 marker.header.frame_id = frame;
80 marker.ns =
"handle_numbers";
86 marker.type = visualization_msgs::Marker::TEXT_VIEW_FACING;
87 marker.action = visualization_msgs::Marker::ADD;
90 marker.scale.z = 0.03;
93 marker.pose.position.x = handles[i / 2][0].getCentroid()(0);
94 marker.pose.position.y = handles[i / 2][0].getCentroid()(1);
95 marker.pose.position.z = handles[i / 2][0].getCentroid()(2) - 0.06;
100 marker.color.g = 0.0;
101 marker.color.b = 0.0;
104 marker.text = boost::lexical_cast < std::string > ((i / 2) + 1);
109 marker.type = visualization_msgs::Marker::CUBE;
110 marker.action = visualization_msgs::Marker::ADD;
113 marker.scale.x = 0.03;
114 marker.scale.y = 0.03;
115 marker.scale.z = 0.001;
118 marker.pose.position.x = marker_array.markers[i - 1].pose.position.x;
119 marker.pose.position.y = marker_array.markers[i - 1].pose.position.y;
120 marker.pose.position.z = marker_array.markers[i - 1].pose.position.z + 0.015;
123 marker.color.a = 1.0;
124 marker.color.r = 1.0;
125 marker.color.g = 1.0;
126 marker.color.b = 1.0;
128 marker_array.markers[i] = marker;
135 std::vector<MarkerArray> &marker_arrays,
MarkerArray &all_handle_markers)
137 marker_arrays.resize(handles.size());
138 std::vector<CylindricalShell> handle_shells;
141 for (std::size_t i = 0; i < handles.size(); i++)
144 for (
int j = 0; j < handles[i].size(); j++)
145 handle_shells.push_back(handles[i][j]);
Visualizer(double marker_lifetime)
Constructor. Set the lifetime of markers in RViz.
MarkerArray createCylinders(const std::vector< CylindricalShell > &list, const std::string &frame)
Create a MarkerArray message from a list of cylindrical shells.
static void poseStampedTFToMsg(const Stamped< Pose > &bt, geometry_msgs::PoseStamped &msg)
visualization_msgs::MarkerArray MarkerArray
void getRotation(Quaternion &q) const
MarkerArray createHandleNumbers(const std::vector< std::vector< CylindricalShell > > &handles, const std::string &frame)
Create a MarkerArray message from a list of cylindrical shells.
void createHandles(const std::vector< std::vector< CylindricalShell > > &handles, const std::string &frame, std::vector< MarkerArray > &marker_arrays, MarkerArray &all_handle_markers)
Create a list of MarkerArray messages and a MarkerArray from a list of handles. The former represents...