TAMSVIZ
Visualization and annotation tool for ROS
marker.cpp
1 // TAMSVIZ
2 // (c) 2020 Philipp Ruppel
3 
4 #include "marker.h"
5 
6 #include "../core/profiler.h"
7 #include "../core/transformer.h"
8 #include "../core/workspace.h"
9 #include "shapes.h"
10 #include "text.h"
11 
12 #include <geometric_shapes/shapes.h>
13 
14 #include <eigen_conversions/eigen_msg.h>
15 
16 inline Eigen::Vector3d toVector3d(const geometry_msgs::Vector3 &p) {
17  return Eigen::Vector3d(p.x, p.y, p.z);
18 }
19 
20 inline Eigen::Vector3d toVector3d(const geometry_msgs::Point &p) {
21  return Eigen::Vector3d(p.x, p.y, p.z);
22 }
23 
24 inline Eigen::Vector3f toVector3f(const geometry_msgs::Point &p) {
25  return Eigen::Vector3f(p.x, p.y, p.z);
26 }
27 
28 inline Eigen::Vector3f toVector3f(const geometry_msgs::Vector3 &p) {
29  return Eigen::Vector3f(p.x, p.y, p.z);
30 }
31 
32 inline Eigen::Vector4f toVector4f(const std_msgs::ColorRGBA &p) {
33  return Color4(p.r, p.g, p.b, p.a).toLinearVector4f();
34 }
35 
36 inline Eigen::Vector4d toVector4d(const std_msgs::ColorRGBA &p) {
37  return Color4(p.r, p.g, p.b, p.a).toLinearVector4f().cast<double>();
38 }
39 
40 inline Color4 toColor4(const std_msgs::ColorRGBA &p) {
41  return Color4(p.r, p.g, p.b, p.a);
42 }
43 
44 void VisualizationMarker::update(const visualization_msgs::Marker &marker) {
45  std::unique_lock<std::mutex> lock(_mutex);
46  PROFILER();
47  std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f>>
48  points;
49  points.reserve(marker.points.size());
50  for (auto &p : marker.points) {
51  points.emplace_back(toVector3f(p));
52  }
53  std::vector<Eigen::Vector4f, Eigen::aligned_allocator<Eigen::Vector4f>>
54  colors;
55  colors.reserve(marker.colors.size());
56  for (auto &c : marker.colors) {
57  colors.emplace_back(toVector4f(c));
58  }
59  Eigen::Vector4f color = toVector4f(marker.color);
60  _pose.setIdentity();
61  _frame = marker.header.frame_id;
62  bool type_changed = (_type != marker.type);
63  _type = marker.type;
64  _color = Color4(1, 1, 1, 1);
65  _render_options = RenderOptions();
66  _text.clear();
67  double radius = marker.scale.x * 0.5;
68  switch (marker.type) {
69  case visualization_msgs::Marker::POINTS:
70  case visualization_msgs::Marker::SPHERE_LIST: {
71  if (_mesh_watcher.changed(marker.type, points, colors, color, radius)) {
72  _mesh = std::make_shared<Mesh>([marker, radius](MeshData &mesh) {
73  for (size_t index = 0; index < marker.points.size(); index++) {
74  auto p = toVector3f(marker.points.at(index));
75  mesh.indices.push_back(mesh.positions.size() + 0);
76  mesh.indices.push_back(mesh.positions.size() + 1);
77  mesh.indices.push_back(mesh.positions.size() + 2);
78  mesh.indices.push_back(mesh.positions.size() + 0);
79  mesh.indices.push_back(mesh.positions.size() + 2);
80  mesh.indices.push_back(mesh.positions.size() + 3);
81  Eigen::Vector4f color = (index < marker.colors.size())
82  ? toVector4f(marker.colors.at(index))
83  : toVector4f(marker.color);
84  for (size_t i = 0; i < 4; i++) {
85  mesh.positions.push_back(p);
86  mesh.colors.push_back(color);
87  }
88  Eigen::Vector4f extra(radius, radius, 1.0, 0.0);
89  // if (marker.type == visualization_msgs::Marker::SPHERE_LIST) {
90  // extra.w() = 1.0;
91  // }
92  mesh.extras.emplace_back(extra);
93  mesh.extras.emplace_back(extra);
94  mesh.extras.emplace_back(extra);
95  mesh.extras.emplace_back(extra);
96  mesh.texcoords.emplace_back(-1, -1);
97  mesh.texcoords.emplace_back(+1, -1);
98  mesh.texcoords.emplace_back(+1, +1);
99  mesh.texcoords.emplace_back(-1, +1);
100  }
101  });
102  }
103  break;
104  }
105  case visualization_msgs::Marker::CUBE_LIST: {
106  if (_mesh_watcher.changed(marker.type, points, colors, color, radius)) {
107  _mesh = std::make_shared<Mesh>([marker, points, colors, color,
108  radius](MeshData &mesh) {
109  static MeshData cube = makeBox();
110  Eigen::Vector3f scale = toVector3f(marker.scale) * 0.5f;
111  {
112  size_t n = cube.positions.size() * points.size();
113  mesh.positions.reserve(n);
114  mesh.colors.reserve(n);
115  mesh.normals.reserve(n);
116  }
117  {
118  size_t n = cube.indices.size() * points.size();
119  mesh.indices.reserve(n);
120  }
121  for (size_t index = 0; index < points.size(); index++) {
122  /*MeshData c = cube;
123  c.scale(scale);
124  c.colorize(index < colors.size() ? colors[index] : color);
125  c.translate(points[index]);
126  mesh += c;*/
127  for (size_t i : cube.indices) {
128  mesh.indices.push_back(mesh.positions.size() + i);
129  }
130  for (auto &p : cube.positions) {
131  mesh.positions.emplace_back(p.cwiseProduct(scale) + points[index]);
132  }
133  for (auto &n : cube.normals) {
134  mesh.normals.emplace_back(n);
135  }
136  if (colors.size() >= points.size()) {
137  for (auto &c : cube.positions) {
138  mesh.colors.push_back(colors[index]);
139  }
140  } else {
141  for (auto &c : cube.positions) {
142  mesh.colors.push_back(color);
143  }
144  }
145  }
146  });
147  }
148  break;
149  }
150  case visualization_msgs::Marker::LINE_LIST: {
151  if (_mesh_watcher.changed(marker.type, points, colors, color, radius)) {
152  _mesh = std::make_shared<Mesh>([marker, radius](MeshData &mesh) {
153  for (size_t line_index = 0; line_index < marker.points.size() / 2;
154  line_index++) {
155  mesh.indices.push_back(mesh.positions.size() + 0);
156  mesh.indices.push_back(mesh.positions.size() + 1);
157  mesh.indices.push_back(mesh.positions.size() + 2);
158  mesh.indices.push_back(mesh.positions.size() + 1);
159  mesh.indices.push_back(mesh.positions.size() + 3);
160  mesh.indices.push_back(mesh.positions.size() + 2);
161  auto a = toVector3f(marker.points.at(line_index * 2 + 0));
162  auto b = toVector3f(marker.points.at(line_index * 2 + 1));
163  mesh.positions.push_back(a);
164  mesh.positions.push_back(a);
165  mesh.positions.push_back(b);
166  mesh.positions.push_back(b);
167  mesh.tangents.push_back(a - b);
168  mesh.tangents.push_back(a - b);
169  mesh.tangents.push_back(a - b);
170  mesh.tangents.push_back(a - b);
171  mesh.extras.emplace_back(+radius, 0.0, 2.0, 0.0);
172  mesh.extras.emplace_back(-radius, 0.0, 2.0, 0.0);
173  mesh.extras.emplace_back(+radius, 0.0, 2.0, 0.0);
174  mesh.extras.emplace_back(-radius, 0.0, 2.0, 0.0);
175  Eigen::Vector4f ca =
176  (line_index * 2 + 0 < marker.colors.size())
177  ? toVector4f(marker.colors.at(line_index * 2 + 0))
178  : toVector4f(marker.color);
179  Eigen::Vector4f cb =
180  (line_index * 2 + 1 < marker.colors.size())
181  ? toVector4f(marker.colors.at(line_index * 2 + 1))
182  : toVector4f(marker.color);
183  mesh.colors.push_back(ca);
184  mesh.colors.push_back(ca);
185  mesh.colors.push_back(cb);
186  mesh.colors.push_back(cb);
187  }
188  });
189  }
190  break;
191  }
192  case visualization_msgs::Marker::LINE_STRIP: {
193  if (_mesh_watcher.changed(marker.type, points, colors, color, radius)) {
194  _mesh = std::make_shared<Mesh>([marker, radius](MeshData &mesh) {
195  for (size_t point_index = 0; point_index + 1 < marker.points.size();
196  point_index++) {
197  mesh.indices.push_back(mesh.positions.size() + 0);
198  mesh.indices.push_back(mesh.positions.size() + 1);
199  mesh.indices.push_back(mesh.positions.size() + 2);
200  mesh.indices.push_back(mesh.positions.size() + 1);
201  mesh.indices.push_back(mesh.positions.size() + 3);
202  mesh.indices.push_back(mesh.positions.size() + 2);
203  auto a = toVector3f(marker.points.at(point_index + 0));
204  auto b = toVector3f(marker.points.at(point_index + 1));
205  mesh.positions.push_back(a);
206  mesh.positions.push_back(a);
207  mesh.positions.push_back(b);
208  mesh.positions.push_back(b);
209  mesh.tangents.push_back(a - b);
210  mesh.tangents.push_back(a - b);
211  mesh.tangents.push_back(a - b);
212  mesh.tangents.push_back(a - b);
213  mesh.extras.emplace_back(+radius, 0.0, 2.0, 0.0);
214  mesh.extras.emplace_back(-radius, 0.0, 2.0, 0.0);
215  mesh.extras.emplace_back(+radius, 0.0, 2.0, 0.0);
216  mesh.extras.emplace_back(-radius, 0.0, 2.0, 0.0);
217  Eigen::Vector4f ca =
218  (point_index + 0 < marker.colors.size())
219  ? toVector4f(marker.colors.at(point_index + 0))
220  : toVector4f(marker.color);
221  Eigen::Vector4f cb =
222  (point_index + 1 < marker.colors.size())
223  ? toVector4f(marker.colors.at(point_index + 1))
224  : toVector4f(marker.color);
225  mesh.colors.push_back(ca);
226  mesh.colors.push_back(ca);
227  mesh.colors.push_back(cb);
228  mesh.colors.push_back(cb);
229  }
230  });
231  }
232  break;
233  }
234  case visualization_msgs::Marker::CUBE:
235  _mesh_watcher.changed();
236  static auto box_mesh = std::make_shared<Mesh>(makeBox());
237  _mesh = box_mesh;
238  _pose = Eigen::Scaling(toVector3d(marker.scale) * 0.5);
239  _color = toColor4(marker.color);
240  break;
241  case visualization_msgs::Marker::SPHERE:
242  _mesh_watcher.changed();
243  static auto sphere_mesh = std::make_shared<Mesh>(makeSphere(32, 16));
244  _mesh = sphere_mesh;
245  _pose = Eigen::Scaling(toVector3d(marker.scale) * 0.5);
246  _color = toColor4(marker.color);
247  break;
248  case visualization_msgs::Marker::CYLINDER:
249  _mesh_watcher.changed();
250  static auto cylinder_mesh = std::make_shared<Mesh>(makeCylinder(32));
251  _mesh = cylinder_mesh;
252  _pose = Eigen::Scaling(toVector3d(marker.scale) * 0.5);
253  _color = toColor4(marker.color);
254  break;
255  case visualization_msgs::Marker::ARROW: {
256  PROFILER("ARROW");
257  if (points.size() >= 2) {
258  if (_mesh_watcher.changed(marker.type, points, marker.scale.x,
259  marker.scale.y, marker.scale.z)) {
260  Eigen::Vector3d a = points.at(0).cast<double>();
261  Eigen::Vector3d b = points.at(1).cast<double>();
262  _mesh = std::make_shared<Mesh>([marker, a, b](MeshData &mesh) {
263  PROFILER("ARROW");
264  double len = (a - b).norm();
265  Eigen::Affine3d pose = Eigen::Affine3d(
266  Eigen::Translation3d(a) *
267  Eigen::AngleAxisd(Eigen::Quaterniond::FromTwoVectors(
268  Eigen::Vector3d::UnitX(), b - a)) *
269  Eigen::Scaling(Eigen::Vector3d(len, len * 0.5, len * 0.5)));
270  float head_length = 0.23;
271  if (marker.scale.z > 0) {
272  head_length = std::max(0.0, std::min(marker.scale.z / len, 1.0));
273  }
274  mesh =
275  Eigen::AngleAxisf(M_PI / 2, Eigen::Vector3f::UnitY()) *
276  (Eigen::Translation3f(0.0f, 0.0f, (1.0f - head_length) * 0.5f) *
277  Eigen::Scaling(0.5f, 0.5f, (1.0f - head_length) * 0.5f) *
278  makeCylinder(32) +
279  Eigen::Translation3f(0.0f, 0.0f, (1.0f - head_length)) *
280  Eigen::Scaling(1.0f, 1.0f, head_length) * makeCone(32));
281  mesh = pose * mesh;
282  });
283  }
284  } else {
285  if (_mesh_watcher.changed(marker.type)) {
286  static auto arrow_mesh = std::make_shared<Mesh>(
287  Eigen::AngleAxisf(M_PI / 2, Eigen::Vector3f::UnitY()) *
288  (Eigen::Translation3f(0.0f, 0.0f, 0.77f * 0.5f) *
289  Eigen::Scaling(0.5f, 0.5f, 0.77f * 0.5f) * makeCylinder(32) +
290  Eigen::Translation3f(0.0f, 0.0f, 0.77f) *
291  Eigen::Scaling(1.0f, 1.0f, 0.23f) * makeCone(32)));
292  _mesh = arrow_mesh;
293  }
294  _pose = Eigen::Scaling(toVector3d(marker.scale));
295  }
296  _color = toColor4(marker.color);
297  break;
298  }
299  case visualization_msgs::Marker::TRIANGLE_LIST: {
300  PROFILER("TRIANGLE_LIST");
301  if (_mesh_watcher.changed(marker.type, points, colors, color)) {
302  _mesh = std::make_shared<Mesh>([points, colors, color](MeshData &mesh) {
303  PROFILER("TRIANGLE_LIST");
304  // throw std::runtime_error("");
305  LOG_DEBUG("triangle list " << points.size() << " " << colors.size());
306  size_t triangle_count = points.size() / 3;
307  size_t vertex_count = triangle_count * 3;
308  if (colors.size() >= vertex_count) {
309  for (size_t vertex_index = 0; vertex_index < vertex_count;
310  vertex_index++) {
311  mesh.positions.push_back(points[vertex_index]);
312  mesh.colors.push_back(colors[vertex_index]);
313  }
314  } else if (colors.size() >= triangle_count) {
315  for (size_t vertex_index = 0; vertex_index < vertex_count;
316  vertex_index++) {
317  mesh.positions.push_back(points[vertex_index]);
318  mesh.colors.push_back(colors[vertex_index / 3]);
319  }
320  } else {
321  for (size_t vertex_index = 0; vertex_index < vertex_count;
322  vertex_index++) {
323  mesh.positions.push_back(points[vertex_index]);
324  mesh.colors.push_back(color);
325  }
326  }
327  mesh.computeNormals();
328  });
329  }
330  _pose = Eigen::Scaling(toVector3d(marker.scale));
331  _render_options.double_sided = true;
332  break;
333  }
334  case visualization_msgs::Marker::TEXT_VIEW_FACING: {
335  PROFILER("TEXT_VIEW_FACING");
336  _mesh_watcher.changed();
337  _text = marker.text;
338  _mesh = nullptr;
339  break;
340  }
341  default:
342  _mesh_watcher.changed();
343  LOG_WARN_THROTTLE(1.0, "unknown marker type " << marker.type);
344  _mesh = nullptr;
345  break;
346  }
347  _scale = marker.scale.x;
348  Eigen::Affine3d pose;
349  tf::poseMsgToEigen(marker.pose, pose);
350  _pose = pose * _pose;
351 }
352 
353 void VisualizationMarker::renderSync(const RenderSyncContext &context) {
354  {
355  std::unique_lock<std::mutex> lock(_mutex);
356  if (!_material) {
357  _material = std::make_shared<Material>();
358  }
359  _material->color().r() = _color.r();
360  _material->color().g() = _color.g();
361  _material->color().b() = _color.b();
362  _material->opacity() = _color.a();
363  if (_mesh) {
364  auto mesh_renderer = std::dynamic_pointer_cast<MeshRenderer>(_renderer);
365  if (!mesh_renderer || _mesh != mesh_renderer->mesh()) {
366  _renderer = create<MeshRenderer>(_mesh, _material, _material_override);
367  }
368  } else if (_text.size()) {
369  auto text_renderer = std::dynamic_pointer_cast<TextRenderer>(_renderer);
370  if (!text_renderer) {
371  _renderer = create<TextRenderer>(_material);
372  }
373  } else {
374  _renderer = nullptr;
375  }
376  if (_renderer) {
377  _renderer->frame(_frame);
378  _renderer->pose(_pose);
379  if (auto r = std::dynamic_pointer_cast<MeshRenderer>(_renderer)) {
380  r->options() = _render_options;
381  }
382  if (auto r = std::dynamic_pointer_cast<TextRenderer>(_renderer)) {
383  r->text(_text);
384  r->size(_scale);
385  }
386  }
387  }
388  SceneNode::renderSync(context);
389 }
390 
391 void VisualizationMarkerArray::_update_nolock(
392  const visualization_msgs::Marker &marker) {
393  if (marker.action == visualization_msgs::Marker::ADD ||
394  marker.action == visualization_msgs::Marker::MODIFY) {
395  auto &m = _markers[std::make_pair(marker.ns, marker.id)];
396  if (!m) {
397  m = create<VisualizationMarker>(_material_override);
398  }
399  m->update(marker);
400  }
401  if (marker.action == visualization_msgs::Marker::DELETE) {
402  _markers.erase(std::make_pair(marker.ns, marker.id));
403  }
404  if (marker.action == visualization_msgs::Marker::DELETEALL) {
405  _markers.clear();
406  }
407 }
408 
409 void VisualizationMarkerArray::update(
410  const visualization_msgs::Marker &marker) {
411  std::unique_lock<std::mutex> lock(_mutex);
412  _update_nolock(marker);
413 }
414 
415 void VisualizationMarkerArray::update(
416  const visualization_msgs::MarkerArray &marker_array) {
417  std::unique_lock<std::mutex> lock(_mutex);
418  for (auto &marker : marker_array.markers) {
419  _update_nolock(marker);
420  }
421 }
422 
423 void VisualizationMarkerArray::renderSync(const RenderSyncContext &context) {
424  std::unique_lock<std::mutex> lock(_mutex);
425  /*for (auto &p : _markers) {
426  LOG_DEBUG("marker " << p.first.first << " " << p.first.second);
427  }
428  LOG_DEBUG("");*/
429  _marker_list.clear();
430  for (auto &p : _markers) {
431  _marker_list.push_back(p.second);
432  }
433  SceneNode::renderSync(context);
434 }
435 
436 MarkerDisplay::MarkerDisplay() {
437  auto *r = _marker_array.get();
438  topic().connect(
439  _marker_array,
440  [r](const std::shared_ptr<const visualization_msgs::Marker> &message) {
441  // LOG_DEBUG("marker message");
442  r->update(*message);
443  });
444 }
445 
446 MarkerArrayDisplay::MarkerArrayDisplay() {
447  auto *r = _marker_array.get();
448  topic().connect(
449  _marker_array,
450  [r](const std::shared_ptr<const visualization_msgs::MarkerArray>
451  &message) { r->update(*message); });
452 }
Definition: mesh.h:11