TAMSVIZ
Visualization and annotation tool for ROS
document.cpp
1 // TAMSVIZ
2 // (c) 2020 Philipp Ruppel
3 
4 #include "document.h"
5 
6 #include "../render/renderer.h"
7 #include "../scene/node.h"
8 #include "bagplayer.h"
9 #include "interaction.h"
10 #include "tracks.h"
11 #include "transformer.h"
12 #include "workspace.h"
13 
14 Display::Display() {}
15 
16 TrackBase::TrackBase() {}
17 
18 float srgbGamma2Linear(float srgb) {
19  if (srgb < 0.04045f) {
20  return srgb * (25.0f / 232.0f);
21  } else {
22  return std::pow((200.0 * srgb + 11.0f) * (1.0f / 211.0f), 12.0 / 5.0);
23  }
24 }
25 
26 std::vector<std::string> WorldDisplay::_listFrames(const Property &) {
27  auto ret = LockScope()->document()->display()->transformer->list();
28  std::sort(ret.begin(), ret.end());
29  return ret;
30 }
31 
32 bool Display::interact(
33  const Interaction &interaction) { // interaction.ignored =
34  // true;
35  return false;
36 }
37 
38 static Eigen::Vector3f srgb2Linear(const Eigen::Vector3f &srgb) {
39  return Eigen::Vector3f(srgbGamma2Linear(srgb.x()), srgbGamma2Linear(srgb.y()),
40  srgbGamma2Linear(srgb.z()));
41 }
42 
43 Eigen::Vector4f Color4::toLinearVector4f() const {
44  Eigen::Vector4f ret;
45  ret.head(3) =
46  srgb2Linear(Eigen::Vector3f((float)r(), (float)g(), (float)b()));
47  ret[3] = (float)a();
48  return ret;
49 }
50 
51 WorldDisplay::WorldDisplay() {
52  transformer = std::make_shared<Transformer>();
53  name() = "Document";
54 }
55 
56 void WorldDisplay::renderSync(const RenderSyncContext &context) {
57  transformer->update(fixedFrame());
58  DisplayGroupBase::renderSync(context);
59  {
60  LightBlock light;
61  light.color =
62  backgroundColor().toLinearVector4f().head(3) * (float)ambientLighting();
63  light.type = (uint32_t)LightType::Ambient;
64  context.render_list->push(light);
65  }
66  /* _current_scene_annotations.clear();
67  {
68  LockScope ws;
69  if (ws->player && ws->document()->timeline()) {
70  auto current_time = ws->player->time();
71  for (auto &track : ws->document()->timeline()->tracks()) {
72  if (auto annotation_track =
73  std::dynamic_pointer_cast<AnnotationTrack>(track)) {
74  if (auto branch = annotation_track->branch()) {
75  for (auto &span : branch->spans()) {
76  if (span->start() <= current_time &&
77  span->start() + span->duration() >= current_time) {
78  for (auto &annotation : span->annotations()) {
79  if (auto scene_annotation =
80  std::dynamic_pointer_cast<SceneAnnotationBase>(
81  annotation)) {
82  _current_scene_annotations.push_back(scene_annotation);
83  }
84  }
85  }
86  }
87  }
88  }
89  }
90  }
91  }
92  for (auto &scene_annotation : _current_scene_annotations) {
93  scene_annotation->renderSync(context);
94  }*/
95 }
96 
97 void WorldDisplay::renderAsync(const RenderAsyncContext &context) {
98  DisplayGroupBase::renderAsync(context);
99  /*for (auto &scene_annotation : _current_scene_annotations) {
100  scene_annotation->renderAsync(context);
101 }*/
102 }
103 
104 void DisplayGroupBase::renderSyncRecursive(const RenderSyncContext &context) {
105  renderSync(context);
106  for (auto &display : displays()) {
107  display->renderSyncRecursive(context);
108  }
109 }
110 
111 Eigen::Isometry3d Orientation::toIsometry3d() const {
112  return Eigen::Translation3d(0, 0, 0) *
113  Eigen::AngleAxisd(yaw() * (M_PI / 180.0), Eigen::Vector3d::UnitZ()) *
114  Eigen::AngleAxisd(pitch() * (M_PI / 180.0), Eigen::Vector3d::UnitY()) *
115  Eigen::AngleAxisd(roll() * (M_PI / 180.0), Eigen::Vector3d::UnitX());
116 }
117 
118 Eigen::Isometry3d Pose::toIsometry3d() const {
119  return Eigen::Translation3d(position()) *
120  Eigen::AngleAxisd(orientation().yaw() * (M_PI / 180.0),
121  Eigen::Vector3d::UnitZ()) *
122  Eigen::AngleAxisd(orientation().pitch() * (M_PI / 180.0),
123  Eigen::Vector3d::UnitY()) *
124  Eigen::AngleAxisd(orientation().roll() * (M_PI / 180.0),
125  Eigen::Vector3d::UnitX());
126 }
127 
128 void Pose::fromIsometry3d(const Eigen::Isometry3d &pose) {
129  position() = pose.translation();
130  Eigen::Vector3d angles = pose.linear().eulerAngles(2, 1, 0);
131  orientation().yaw() = angles.x() * (180.0 / M_PI);
132  orientation().pitch() = angles.y() * (180.0 / M_PI);
133  orientation().roll() = angles.z() * (180.0 / M_PI);
134 }
135 
136 void Display::refreshRecursive() { refresh(); }
137 
138 void Display::refresh() {}
139 
140 void DisplayGroupBase::refreshRecursive() {
141  for (auto &display : displays()) {
142  display->refreshRecursive();
143  }
144  refresh();
145 }