TAMSVIZ
Visualization and annotation tool for ROS
node.h
1 // TAMSVIZ
2 // (c) 2020 Philipp Ruppel
3 
4 #pragma once
5 
6 #include "../core/document.h"
7 #include "../core/transformer.h"
8 
9 #include <list>
10 #include <memory>
11 
12 #include <Eigen/Dense>
13 
14 class SceneNode;
15 
16 struct SceneContext {
17  std::vector<std::shared_ptr<SceneNode>> nodes;
18 };
19 
20 class SceneNode : public std::enable_shared_from_this<SceneNode> {
21 private:
22  std::mutex _mutex;
23  bool _has_parent = false;
24  bool _visible = true;
25  Frame _frame;
26  Eigen::Affine3d _pose = Eigen::Affine3d::Identity();
27  std::list<std::weak_ptr<SceneNode>> _children;
28  std::vector<std::shared_ptr<SceneNode>> _render_list;
29  Eigen::Affine3d _frame_pose = Eigen::Affine3d::Identity();
30 
31 public:
32  SceneNode();
33  SceneNode(const SceneNode &) = delete;
34  SceneNode &operator=(const SceneNode &) = delete;
35  ~SceneNode();
36  void connect(const std::shared_ptr<SceneNode> &child);
37  void renderSyncRecursive(const RenderSyncContext &context,
38  SceneContext &scene_context);
39  virtual void renderSync(const RenderSyncContext &context);
40  virtual void renderAsync(const RenderAsyncContext &context);
41  Eigen::Affine3d renderPose() const { return _frame_pose * _pose; }
42  const Eigen::Affine3d &framePose() const { return _frame_pose; }
43  virtual bool pick(uint32_t id) const;
44  virtual bool interact(const Interaction &interaction);
45  const Frame &frame() const { return _frame; }
46  void frame(const Frame &frame) { _frame = frame; }
47  void frame(const std::string &name) { _frame.name(name); }
48  void pose(const Eigen::Isometry3d &pose) { _pose = Eigen::Affine3d(pose); }
49  void pose(const Eigen::Affine3d &pose) { _pose = pose; }
50  const Eigen::Affine3d &pose() const { return _pose; }
51  void show() { _visible = true; }
52  void hide() { _visible = false; }
53  bool visible() const { return _visible; }
54  bool visible(bool v) { _visible = v; }
55  template <class T, class... Args>
56  std::shared_ptr<T> create(const Args &... args) {
57  auto instance = std::make_shared<T>(args...);
58  connect(instance);
59  return instance;
60  }
61 };
Definition: node.h:20