TAMSVIZ
Visualization and annotation tool for ROS
mesh.cpp
1 // TAMSVIZ
2 // (c) 2020 Philipp Ruppel
3 
4 #include "mesh.h"
5 
6 #include "../core/interaction.h"
7 #include "material.h"
8 #include "mesh.h"
9 
10 bool MeshRenderer::pick(uint32_t id) const {
11  return _material && _material->id() == id;
12 }
13 
14 bool MeshRenderer::interact(const Interaction &interaction) {
15  if (_interact_callback && pick(interaction.id)) {
16  _interact_callback(interaction);
17  return true;
18  }
19  return false;
20 }
21 
22 MeshRenderer::MeshRenderer(const std::shared_ptr<Mesh> &mesh,
23  const std::shared_ptr<MaterialRenderer> &material) {
24  _mesh = mesh;
25  _material = material;
26 }
27 
28 MeshRenderer::MeshRenderer(
29  const std::shared_ptr<Mesh> &mesh, std::shared_ptr<const Material> material,
30  std::shared_ptr<const MaterialOverride> material_override)
31  : MeshRenderer(mesh, std::make_shared<MaterialRenderer>(
32  material, material_override)) {}
33 
34 MeshRenderer::~MeshRenderer() {}
35 
36 void MeshRenderer::renderSync(const RenderSyncContext &context) {
37  _parent_pose = context.pose;
38  _material->renderSync(context);
39  _render_options_2 = _render_options;
40 }
41 
42 void MeshRenderer::renderAsync(const RenderAsyncContext &context) {
43  _material->renderAsync(context);
44  if (visible()) {
45  context.render_list->push(_material->block());
46  context.render_list->push(_mesh, _render_options_2);
47  InstanceBlock instance;
48  instance.setPose(_parent_pose.matrix().cast<float>());
49  context.render_list->push(instance);
50  }
51 }
52 
53 void MeshRenderer::options(const RenderOptions &options) {
54  _render_options = options;
55 }
56 
57 MeshRenderer::MeshRenderer(const std::shared_ptr<Mesh> &mesh,
58  std::shared_ptr<const Material> material,
59  const Eigen::Isometry3d &pose)
60  : MeshRenderer(mesh, material) {
61  this->pose(pose);
62 }
63 
64 MeshRenderer::MeshRenderer(
65  const std::shared_ptr<Mesh> &mesh, std::shared_ptr<const Material> material,
66  const std::function<void(const Interaction &)> &interact_callback)
67  : MeshRenderer(mesh, material) {
68  _interact_callback = interact_callback;
69 }
70 
71 const std::shared_ptr<Mesh> &MeshRenderer::mesh() const { return _mesh; }
72 
73 const std::shared_ptr<MaterialRenderer> &MeshRenderer::materialRenderer() {
74  return _material;
75 }
76 
77 const RenderOptions &MeshRenderer::options() const { return _render_options; }
78 
79 RenderOptions &MeshRenderer::options() { return _render_options; }
80 
81 void InstancedMeshRenderer::renderAsync(const RenderAsyncContext &context) {
82  _material->renderAsync(context);
83  if (visible()) {
84  context.render_list->push(_material->block());
85  context.render_list->push(_mesh, _render_options_2);
86  for (auto &pose : _poses) {
87  InstanceBlock instance;
88  instance.setPose(pose.matrix().cast<float>());
89  context.render_list->push(instance);
90  }
91  }
92 }
93 
94 InstancedMeshRenderer::InstancedMeshRenderer(
95  const std::shared_ptr<Mesh> &mesh, std::shared_ptr<const Material> material)
96  : MeshRenderer(mesh, material) {}
97 
98 void InstancedMeshRenderer::clearInstances() { _poses.clear(); }
99 
100 void InstancedMeshRenderer::addInstance(const Eigen::Isometry3d &pose) {
101  _poses.push_back(pose);
102 }