6 #include "../core/profiler.h" 7 #include "../core/transformer.h" 8 #include "../core/workspace.h" 12 #include <geometric_shapes/shapes.h> 14 #include <eigen_conversions/eigen_msg.h> 16 inline Eigen::Vector3d toVector3d(
const geometry_msgs::Vector3 &p) {
17 return Eigen::Vector3d(p.x, p.y, p.z);
20 inline Eigen::Vector3d toVector3d(
const geometry_msgs::Point &p) {
21 return Eigen::Vector3d(p.x, p.y, p.z);
24 inline Eigen::Vector3f toVector3f(
const geometry_msgs::Point &p) {
25 return Eigen::Vector3f(p.x, p.y, p.z);
28 inline Eigen::Vector3f toVector3f(
const geometry_msgs::Vector3 &p) {
29 return Eigen::Vector3f(p.x, p.y, p.z);
32 inline Eigen::Vector4f toVector4f(
const std_msgs::ColorRGBA &p) {
33 return Color4(p.r, p.g, p.b, p.a).toLinearVector4f();
36 inline Eigen::Vector4d toVector4d(
const std_msgs::ColorRGBA &p) {
37 return Color4(p.r, p.g, p.b, p.a).toLinearVector4f().cast<
double>();
40 inline Color4 toColor4(
const std_msgs::ColorRGBA &p) {
41 return Color4(p.r, p.g, p.b, p.a);
44 void VisualizationMarker::update(
const visualization_msgs::Marker &marker) {
45 std::unique_lock<std::mutex> lock(_mutex);
47 std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f>>
49 points.reserve(marker.points.size());
50 for (
auto &p : marker.points) {
51 points.emplace_back(toVector3f(p));
53 std::vector<Eigen::Vector4f, Eigen::aligned_allocator<Eigen::Vector4f>>
55 colors.reserve(marker.colors.size());
56 for (
auto &c : marker.colors) {
57 colors.emplace_back(toVector4f(c));
59 Eigen::Vector4f color = toVector4f(marker.color);
61 _frame = marker.header.frame_id;
62 bool type_changed = (_type != marker.type);
64 _color =
Color4(1, 1, 1, 1);
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);
88 Eigen::Vector4f extra(radius, radius, 1.0, 0.0);
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);
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,
110 Eigen::Vector3f scale = toVector3f(marker.scale) * 0.5f;
112 size_t n = cube.positions.size() * points.size();
113 mesh.positions.reserve(n);
114 mesh.colors.reserve(n);
115 mesh.normals.reserve(n);
118 size_t n = cube.indices.size() * points.size();
119 mesh.indices.reserve(n);
121 for (
size_t index = 0; index < points.size(); index++) {
127 for (
size_t i : cube.indices) {
128 mesh.indices.push_back(mesh.positions.size() + i);
130 for (
auto &p : cube.positions) {
131 mesh.positions.emplace_back(p.cwiseProduct(scale) + points[index]);
133 for (
auto &n : cube.normals) {
134 mesh.normals.emplace_back(n);
136 if (colors.size() >= points.size()) {
137 for (
auto &c : cube.positions) {
138 mesh.colors.push_back(colors[index]);
141 for (
auto &c : cube.positions) {
142 mesh.colors.push_back(color);
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;
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);
176 (line_index * 2 + 0 < marker.colors.size())
177 ? toVector4f(marker.colors.at(line_index * 2 + 0))
178 : toVector4f(marker.color);
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);
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();
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);
218 (point_index + 0 < marker.colors.size())
219 ? toVector4f(marker.colors.at(point_index + 0))
220 : toVector4f(marker.color);
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);
234 case visualization_msgs::Marker::CUBE:
235 _mesh_watcher.changed();
236 static auto box_mesh = std::make_shared<Mesh>(makeBox());
238 _pose = Eigen::Scaling(toVector3d(marker.scale) * 0.5);
239 _color = toColor4(marker.color);
241 case visualization_msgs::Marker::SPHERE:
242 _mesh_watcher.changed();
243 static auto sphere_mesh = std::make_shared<Mesh>(makeSphere(32, 16));
245 _pose = Eigen::Scaling(toVector3d(marker.scale) * 0.5);
246 _color = toColor4(marker.color);
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);
255 case visualization_msgs::Marker::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) {
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));
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) *
279 Eigen::Translation3f(0.0f, 0.0f, (1.0f - head_length)) *
280 Eigen::Scaling(1.0f, 1.0f, head_length) * makeCone(32));
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)));
294 _pose = Eigen::Scaling(toVector3d(marker.scale));
296 _color = toColor4(marker.color);
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");
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;
311 mesh.positions.push_back(points[vertex_index]);
312 mesh.colors.push_back(colors[vertex_index]);
314 }
else if (colors.size() >= triangle_count) {
315 for (
size_t vertex_index = 0; vertex_index < vertex_count;
317 mesh.positions.push_back(points[vertex_index]);
318 mesh.colors.push_back(colors[vertex_index / 3]);
321 for (
size_t vertex_index = 0; vertex_index < vertex_count;
323 mesh.positions.push_back(points[vertex_index]);
324 mesh.colors.push_back(color);
327 mesh.computeNormals();
330 _pose = Eigen::Scaling(toVector3d(marker.scale));
331 _render_options.double_sided =
true;
334 case visualization_msgs::Marker::TEXT_VIEW_FACING: {
335 PROFILER(
"TEXT_VIEW_FACING");
336 _mesh_watcher.changed();
342 _mesh_watcher.changed();
343 LOG_WARN_THROTTLE(1.0,
"unknown marker type " << marker.type);
347 _scale = marker.scale.x;
348 Eigen::Affine3d pose;
349 tf::poseMsgToEigen(marker.pose, pose);
350 _pose = pose * _pose;
355 std::unique_lock<std::mutex> lock(_mutex);
357 _material = std::make_shared<Material>();
359 _material->color().r() = _color.r();
360 _material->color().g() = _color.g();
361 _material->color().b() = _color.b();
362 _material->opacity() = _color.a();
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);
368 }
else if (_text.size()) {
369 auto text_renderer = std::dynamic_pointer_cast<
TextRenderer>(_renderer);
370 if (!text_renderer) {
371 _renderer = create<TextRenderer>(_material);
377 _renderer->frame(_frame);
378 _renderer->pose(_pose);
379 if (
auto r = std::dynamic_pointer_cast<MeshRenderer>(_renderer)) {
380 r->options() = _render_options;
382 if (
auto r = std::dynamic_pointer_cast<TextRenderer>(_renderer)) {
388 SceneNode::renderSync(context);
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)];
397 m = create<VisualizationMarker>(_material_override);
401 if (marker.action == visualization_msgs::Marker::DELETE) {
402 _markers.erase(std::make_pair(marker.ns, marker.id));
404 if (marker.action == visualization_msgs::Marker::DELETEALL) {
409 void VisualizationMarkerArray::update(
410 const visualization_msgs::Marker &marker) {
411 std::unique_lock<std::mutex> lock(_mutex);
412 _update_nolock(marker);
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);
424 std::unique_lock<std::mutex> lock(_mutex);
429 _marker_list.clear();
430 for (
auto &p : _markers) {
431 _marker_list.push_back(p.second);
433 SceneNode::renderSync(context);
436 MarkerDisplay::MarkerDisplay() {
437 auto *r = _marker_array.get();
440 [r](
const std::shared_ptr<const visualization_msgs::Marker> &message) {
446 MarkerArrayDisplay::MarkerArrayDisplay() {
447 auto *r = _marker_array.get();
450 [r](
const std::shared_ptr<const visualization_msgs::MarkerArray>
451 &message) { r->update(*message); });