visualizer.cpp
Go to the documentation of this file.
2 
3 
4 Visualizer::Visualizer(double marker_lifetime)
5 {
6  this->marker_lifetime = marker_lifetime;
7 }
8 
9 MarkerArray Visualizer::createCylinders(const std::vector<CylindricalShell> &list, const std::string &frame)
10 {
11  // create and resize a marker array message
12  MarkerArray marker_array;
13  marker_array.markers.resize(list.size());
14 
15  for (std::size_t i = 0; i < list.size(); i++)
16  {
17  // create marker
18  visualization_msgs::Marker marker;
19  marker.header.frame_id = frame;
20  marker.header.stamp = ros::Time::now();
21 
22  // namespace and id to give the marker a unique identification
23  marker.ns = "cylinders_ns";
24  marker.id = i;
25 
26  // how long the marker exists
27  marker.lifetime = ros::Duration(this->marker_lifetime);
28 
29  // type of marker (cylinder)
30  marker.type = visualization_msgs::Marker::CYLINDER;
31  marker.action = visualization_msgs::Marker::ADD;
32 
33  // marker position
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);
37 
38  // marker rotation
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),
44  axis(2));
45  tf::Quaternion quaternion;
46  rotation_matrix.getRotation(quaternion);
47  tf::Stamped<tf::Transform> cylinder_tf_pose(tf::Transform(quaternion), marker.header.stamp, frame);
48  tf::poseStampedTFToMsg(cylinder_tf_pose, cylinder_pose_msg);
49  marker.pose.orientation = cylinder_pose_msg.pose.orientation;
50 
51  // marker scale
52  marker.scale.x = list[i].getRadius() * 2; // diameter in x-direction
53  marker.scale.y = list[i].getRadius() * 2; // diameter in y-direction
54  marker.scale.z = list[i].getExtent(); // height
55 
56  // marker color and transparency
57  marker.color.a = 0.3;
58  marker.color.r = 0;
59  marker.color.g = 255;
60  marker.color.b = 255;
61 
62  marker_array.markers[i] = marker;
63  }
64 
65  return marker_array;
66 }
67 
68 MarkerArray Visualizer::createHandleNumbers(const std::vector<std::vector<CylindricalShell> > &handles,
69  const std::string &frame)
70 {
71  // create and resize a marker array message
72  MarkerArray marker_array;
73  marker_array.markers.resize(handles.size() * 2);
74 
75  for (std::size_t i = 0; i < handles.size() * 2; i++)
76  {
77  visualization_msgs::Marker marker;
78  marker.header.frame_id = frame;
79  marker.header.stamp = ros::Time::now();
80  marker.ns = "handle_numbers";
81  marker.id = i;
82  marker.lifetime = ros::Duration(this->marker_lifetime);
83 
84  if (i % 2 == 0)
85  {
86  marker.type = visualization_msgs::Marker::TEXT_VIEW_FACING;
87  marker.action = visualization_msgs::Marker::ADD;
88 
89  // height of an upper-case "A"
90  marker.scale.z = 0.03;
91 
92  // marker position
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;
96 
97  // marker color and transparency
98  marker.color.a = 1.0;
99  marker.color.r = 1.0;
100  marker.color.g = 0.0;
101  marker.color.b = 0.0;
102 
103  // displayed text
104  marker.text = boost::lexical_cast < std::string > ((i / 2) + 1);
105  }
106  else
107  {
108  // type of marker (cylinder)
109  marker.type = visualization_msgs::Marker::CUBE;
110  marker.action = visualization_msgs::Marker::ADD;
111 
112  // height of an upper-case "A"
113  marker.scale.x = 0.03;
114  marker.scale.y = 0.03;
115  marker.scale.z = 0.001;
116 
117  // marker position
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;
121 
122  // marker color and transparency
123  marker.color.a = 1.0;
124  marker.color.r = 1.0;
125  marker.color.g = 1.0;
126  marker.color.b = 1.0;
127  }
128  marker_array.markers[i] = marker;
129  }
130 
131  return marker_array;
132 }
133 
134 void Visualizer::createHandles(const std::vector<std::vector<CylindricalShell> > &handles, const std::string &frame,
135  std::vector<MarkerArray> &marker_arrays, MarkerArray &all_handle_markers)
136 {
137  marker_arrays.resize(handles.size());
138  std::vector<CylindricalShell> handle_shells;
139  int k = 0;
140 
141  for (std::size_t i = 0; i < handles.size(); i++)
142  {
143  marker_arrays[i] = this->createCylinders(handles[i], frame);
144  for (int j = 0; j < handles[i].size(); j++)
145  handle_shells.push_back(handles[i][j]);
146  }
147 
148  all_handle_markers = this->createCylinders(handle_shells, frame);
149 }
Visualizer(double marker_lifetime)
Constructor. Set the lifetime of markers in RViz.
Definition: visualizer.cpp:4
MarkerArray createCylinders(const std::vector< CylindricalShell > &list, const std::string &frame)
Create a MarkerArray message from a list of cylindrical shells.
Definition: visualizer.cpp:9
static void poseStampedTFToMsg(const Stamped< Pose > &bt, geometry_msgs::PoseStamped &msg)
visualization_msgs::MarkerArray MarkerArray
Definition: visualizer.h:42
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.
Definition: visualizer.cpp:68
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...
Definition: visualizer.cpp:134
static Time now()
double marker_lifetime
Definition: visualizer.h:85


handle_detector
Author(s):
autogenerated on Mon Jun 10 2019 13:29:00