TAMSVIZ
Visualization and annotation tool for ROS
transformer.cpp
1 // TAMSVIZ
2 // (c) 2020 Philipp Ruppel
3 
4 #include "transformer.h"
5 
6 #include "profiler.h"
7 #include "timeseries.h"
8 #include "topic.h"
9 #include "workspace.h"
10 
11 #include <geometry_msgs/TransformStamped.h>
12 #include <tf/tfMessage.h>
13 #include <tf2_msgs/TFMessage.h>
14 
15 #include <unordered_map>
16 #include <unordered_set>
17 
18 #include <eigen_conversions/eigen_msg.h>
19 
21  mutable std::mutex _mutex;
22  const std::function<void(
23  const std::shared_ptr<const geometry_msgs::TransformStamped> &)>
24  _callback;
25  std::unordered_map<
26  std::string,
27  std::map<int64_t, std::shared_ptr<const geometry_msgs::TransformStamped>>>
28  _data;
29  std::unordered_set<std::string> _modified;
30  void _push(const std::shared_ptr<geometry_msgs::TransformStamped> &msg,
31  int64_t message_time, int64_t start, int64_t end) {
32  auto &sequence = _data[msg->child_frame_id];
33  _modified.insert(msg->child_frame_id);
34  sequence.emplace(message_time, msg);
35  while (!sequence.empty() && sequence.begin()->first < start) {
36  sequence.erase(sequence.begin());
37  }
38  while (!sequence.empty() && sequence.rbegin()->first > end) {
39  auto it = sequence.end();
40  --it;
41  sequence.erase(it);
42  }
43  }
44 
45 public:
47  const std::function<
48  void(const std::shared_ptr<const geometry_msgs::TransformStamped> &)>
49  &callback)
50  : _callback(callback) {}
53  operator=(const TransformMessageListener &) = delete;
54  virtual void push(const std::shared_ptr<const Message> &message,
55  int64_t start, int64_t end) override {
56  PROFILER("TransformMessageListener");
57  std::unique_lock<std::mutex> lock(_mutex);
58  if (auto msg = message->instantiate<tf2_msgs::TFMessage>()) {
59  for (auto &tf : msg->transforms) {
60  _push(std::make_shared<geometry_msgs::TransformStamped>(tf),
61  message->time().toNSec(), start, end);
62  }
63  }
64  if (auto msg = message->instantiate<tf::tfMessage>()) {
65  for (auto &tf : msg->transforms) {
66  _push(std::make_shared<geometry_msgs::TransformStamped>(tf),
67  message->time().toNSec(), start, end);
68  }
69  }
70  }
71  virtual void commit() override {
72  std::unique_lock<std::mutex> lock(_mutex);
73  for (auto &m : _modified) {
74  auto &sequence = _data[m];
75  if (!sequence.empty()) {
76  auto it = sequence.end();
77  --it;
78  _callback(it->second);
79  }
80  }
81  _modified.clear();
82  }
83 };
84 
85 typedef Eigen::Transform<double, 3, Eigen::Isometry, Eigen::DontAlign>
86  Isometry3du;
87 
88 static void normalizeFrameName(std::string &name) {
89  if (!name.empty() && name.front() == '/') {
90  name.erase(0, 1);
91  }
92 }
93 
94 class FrameManager {
95 
96 public:
97  std::mutex _mutex;
98  std::unordered_map<std::string, int64_t> _references;
99  static std::shared_ptr<FrameManager> instance() {
100  static auto instance = std::make_shared<FrameManager>();
101  return instance;
102  }
103  void count(std::string name, int64_t d) {
104  normalizeFrameName(name);
105  if (!name.empty()) {
106  bool redraw = false;
107  {
108  std::lock_guard<std::mutex> lock(_mutex);
109  int64_t &r = _references[name];
110  // LOG_DEBUG("frame " << name << " refcount " << r << " d " << d);
111  if (r == 0) {
112  redraw = true;
113  }
114  r += d;
115  // LOG_DEBUG("frame " << name << " refcount " << r << " d " << d);
116  if (r < 0) {
117  throw std::runtime_error("frame reference counter corrupted");
118  }
119  }
120  if (redraw) {
121  GlobalEvents::instance()->redraw();
122  }
123  }
124  }
125  bool check(std::string name) {
126  normalizeFrameName(name);
127  bool used = false;
128  if (!name.empty()) {
129  std::lock_guard<std::mutex> lock(_mutex);
130  auto it = _references.find(name);
131  if (it != _references.end()) {
132  if (it->second > 0) {
133  used = true;
134  }
135  }
136  }
137  return used;
138  }
139 };
140 
142  std::mutex _mutex;
143  std::vector<std::shared_ptr<void>> _subscribers;
144  std::vector<std::string> _index_to_name;
145  std::unordered_map<std::string, size_t> _name_to_index_map;
146  std::unordered_map<size_t, std::unordered_map<size_t, Isometry3du>>
147  _connections;
148  std::vector<Optional<Eigen::Isometry3d>,
149  Eigen::aligned_allocator<Optional<Eigen::Isometry3d>>>
150  _poses;
151  std::vector<size_t> _current;
152  std::vector<size_t> _next;
153  std::vector<uint8_t> _visited;
154  std::vector<ssize_t> _parents;
155  std::vector<uint8_t> _used;
156  volatile bool _redraw_emitted = false;
157 
158  void clear() {
159  std::unique_lock<std::mutex> lock(_mutex);
160  _index_to_name.clear();
161  _name_to_index_map.clear();
162  _connections.clear();
163  _poses.clear();
164  _current.clear();
165  _next.clear();
166  _visited.clear();
167  _parents.clear();
168  _used.clear();
169  _redraw_emitted = false;
170  }
171 
172  size_t nameToIndexCreate(std::string name) {
173  normalizeFrameName(name);
174  {
175  auto it = _name_to_index_map.find(name);
176  if (it != _name_to_index_map.end()) {
177  return it->second;
178  }
179  }
180  _name_to_index_map[name] = _index_to_name.size();
181  _index_to_name.push_back(name);
182  {
183  auto it = _name_to_index_map.find(name);
184  if (it != _name_to_index_map.end()) {
185  return it->second;
186  }
187  }
188  throw std::runtime_error("");
189  }
190 
191  ssize_t tryNameToIndex(std::string name) {
192  normalizeFrameName(name);
193  {
194  auto it = _name_to_index_map.find(name);
195  if (it != _name_to_index_map.end()) {
196  return it->second;
197  }
198  }
199  return -1;
200  }
201 
202  void push(const geometry_msgs::TransformStamped &tf) {
203  Eigen::Isometry3d transform;
204  tf::transformMsgToEigen(tf.transform, transform);
205  Eigen::Isometry3d transform_inverse = transform.inverse();
206  if (transform.matrix().allFinite() &&
207  transform_inverse.matrix().allFinite()) {
208  bool _redraw = false;
209  {
210  std::unique_lock<std::mutex> lock(_mutex);
211  auto parent = nameToIndexCreate(tf.header.frame_id);
212  auto child = nameToIndexCreate(tf.child_frame_id);
213  if (parent != child) {
214  if ((parent < _poses.size() && (bool)_poses[parent]) !=
215  (child < _poses.size() && (bool)_poses[child])) {
216  _redraw = true;
217  }
218  if ((_connections[parent][child].matrix() != transform.matrix()) &&
219  ((parent < _used.size() && _used[parent]) &&
220  (child < _used.size() && _used[child]))) {
221  _redraw = true;
222  }
223  _connections[parent][child] = transform;
224  _connections[child][parent] = transform_inverse;
225  }
226  }
227  if (_redraw) {
228  if (!_redraw_emitted) {
229  _redraw_emitted = true;
230  // LOG_DEBUG("redraw begin");
231  GlobalEvents::instance()->redraw();
232  // LOG_DEBUG("redraw end");
233  }
234  }
235  }
236  }
237 
238  void update(const std::string &root_name) {
239  std::unique_lock<std::mutex> lock(_mutex);
240  _redraw_emitted = false;
241  size_t root = nameToIndexCreate(root_name);
242  _poses.clear();
243  _poses.resize(_index_to_name.size(), Optional<Eigen::Isometry3d>());
244  _parents.clear();
245  _parents.resize(_poses.size(), -1);
246  _used.clear();
247  _used.resize(_poses.size(), 0);
248  _poses[root] = Eigen::Isometry3d::Identity();
249  _current.clear();
250  _current.push_back(root);
251  _visited.clear();
252  _visited.resize(_index_to_name.size(), 0);
253  bool any = false;
254  while (!_current.empty()) {
255  _next.clear();
256  for (size_t curr : _current) {
257  for (auto &conn : _connections[curr]) {
258  if (!_visited[conn.first]) {
259  any = true;
260  _visited[conn.first] = true;
261  _poses[conn.first] = *_poses[curr] * conn.second;
262  _parents[conn.first] = curr;
263  _next.emplace_back(conn.first);
264  }
265  }
266  }
267  _current = _next;
268  }
269  {
270  // LOG_DEBUG("mark frames");
271  auto manager = FrameManager::instance();
272  std::lock_guard<std::mutex> lock(manager->_mutex);
273  for (auto &p : manager->_references) {
274  if (p.second > 0) {
275  ssize_t i = tryNameToIndex(p.first);
276  while (i >= 0 && !_used[i]) {
277  _used[i] = 1;
278  i = _parents[i];
279  }
280  }
281  }
282  }
283  if (0) {
284  for (size_t i = 0; i < _used.size(); i++) {
285  if (_used[i]) {
286  LOG_DEBUG(i << " " << _index_to_name[i] << " " << (int)_used[i]);
287  }
288  }
289  }
290  if (!any) {
291  LOG_WARN_THROTTLE(1.0, "no connections from base frame: " << root_name);
292  }
293  }
294 
295  Optional<Eigen::Isometry3d> lookup(const std::string &name) {
296  std::unique_lock<std::mutex> lock(_mutex);
297  ssize_t index = tryNameToIndex(name);
298  if (index >= 0 && index < _poses.size()) {
299  return _poses[index];
300  } else {
302  }
303  }
304 
305  std::vector<std::string> list() {
306  std::unordered_set<size_t> indices;
307  {
308  std::unique_lock<std::mutex> lock(_mutex);
309  for (auto &a : _connections) {
310  for (auto &b : a.second) {
311  indices.insert(a.first);
312  indices.insert(b.first);
313  }
314  }
315  }
316  std::vector<std::string> ret;
317  for (auto i : indices) {
318  ret.push_back(_index_to_name[i]);
319  }
320  return ret;
321  }
322 
323  void push(const std::shared_ptr<const Message> &message) {
324  if (auto msg = message->instantiate<tf2_msgs::TFMessage>()) {
325  for (auto &tf : msg->transforms) {
326  push(tf);
327  }
328  }
329  if (auto msg = message->instantiate<tf::tfMessage>()) {
330  for (auto &tf : msg->transforms) {
331  push(tf);
332  }
333  }
334  if (auto msg = message->instantiate<geometry_msgs::TransformStamped>()) {
335  push(*msg);
336  }
337  }
338 };
339 
340 Transformer::Transformer(bool subscribe) {
341  LOG_DEBUG("Transformer ctor");
342  _data = std::make_shared<Data>();
343  if (subscribe) {
344  auto _data = this->_data;
345  std::thread([_data]() {
346  if (_data->_subscribers.empty()) {
347  {
348  auto topic = "/tf_static";
349  auto *data = _data.get();
350  auto subscriber = std::make_shared<Subscriber<Message>>(
351  topic, _data,
352  [data](const std::shared_ptr<const Message> &message) {
353  PROFILER("Transformer");
354  data->push(message);
355  },
356  false);
357  subscriber->topic()->connected.connect(_data,
358  [data]() { data->clear(); });
359  _data->_subscribers.push_back(subscriber);
360  }
361  {
362  auto topic = "/tf";
363  std::weak_ptr<Data> data = _data;
364  auto subscriber = std::make_shared<TimeSeriesSubscriber>(topic);
365  subscriber->duration(0.5);
366  _data->_subscribers.push_back(subscriber);
367  auto listener = std::make_shared<TransformMessageListener>(
368  [data](
369  const std::shared_ptr<const geometry_msgs::TransformStamped>
370  &message) {
371  if (auto d = data.lock()) {
372  PROFILER("Transformer");
373  d->push(*message);
374  }
375  });
376  subscriber->addListener(listener);
377  _data->_subscribers.push_back(listener);
378  }
379  }
380  })
381  .detach();
382  }
383 }
384 
385 Transformer::~Transformer() { LOG_DEBUG("Transformer dtor"); }
386 
387 void Transformer::clear() { _data->clear(); }
388 
389 void Transformer::update(const std::string &root) {
390  _root_name = root;
391  _data->update(root);
392 }
393 
394 void Transformer::push(const std::shared_ptr<const Message> &message) {
395  _data->push(message);
396 }
397 
398 std::vector<std::string> Transformer::list() { return _data->list(); }
399 
400 /*
401 Optional<Eigen::Isometry3d> Transformer::lookup(const Frame &frame) {
402  return _data->lookup(frame.name());
403 }
404 */
405 
406 Frame::Frame() {}
407 
408 Frame::Frame(const std::string &name) : _name(name) {}
409 
410 Frame::Frame(const Frame &other) { _name = other._name; }
411 
412 Frame &Frame::operator=(const Frame &other) {
413  if (other._name != _name) {
414  if (_active) {
415  FrameManager::instance()->count(other._name, +1);
416  FrameManager::instance()->count(_name, -1);
417  }
418  _name = other._name;
419  }
420  return *this;
421 }
422 
423 void Frame::name(const std::string &name) {
424  if (name != _name) {
425  if (_active) {
426  FrameManager::instance()->count(name, +1);
427  FrameManager::instance()->count(_name, -1);
428  }
429  _name = name;
430  }
431 }
432 
433 Frame::~Frame() {
434  if (_active) {
435  FrameManager::instance()->count(_name, -1);
436  }
437 }
438 
440 Frame::pose(const std::shared_ptr<Transformer> &transformer) {
441  if (!_active) {
442  _active = true;
443  FrameManager::instance()->count(_name, +1);
444  }
445  return transformer->_data->lookup(_name);
446 }
447 
449  PropertyAttributes *attributes) {
450  attributes->list = [](const Property &property) {
451  return LockScope()->document()->display()->transformer->list();
452  };
453 }