4 #include "transformer.h" 7 #include "timeseries.h" 11 #include <geometry_msgs/TransformStamped.h> 12 #include <tf/tfMessage.h> 13 #include <tf2_msgs/TFMessage.h> 15 #include <unordered_map> 16 #include <unordered_set> 18 #include <eigen_conversions/eigen_msg.h> 21 mutable std::mutex _mutex;
22 const std::function<void(
23 const std::shared_ptr<const geometry_msgs::TransformStamped> &)>
27 std::map<int64_t, std::shared_ptr<const geometry_msgs::TransformStamped>>>
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());
38 while (!sequence.empty() && sequence.rbegin()->first > end) {
39 auto it = sequence.end();
48 void(
const std::shared_ptr<const geometry_msgs::TransformStamped> &)>
50 : _callback(callback) {}
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);
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);
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();
78 _callback(it->second);
85 typedef Eigen::Transform<double, 3, Eigen::Isometry, Eigen::DontAlign>
88 static void normalizeFrameName(std::string &name) {
89 if (!name.empty() && name.front() ==
'/') {
98 std::unordered_map<std::string, int64_t> _references;
99 static std::shared_ptr<FrameManager> instance() {
100 static auto instance = std::make_shared<FrameManager>();
103 void count(std::string name, int64_t d) {
104 normalizeFrameName(name);
108 std::lock_guard<std::mutex> lock(_mutex);
109 int64_t &r = _references[name];
117 throw std::runtime_error(
"frame reference counter corrupted");
121 GlobalEvents::instance()->redraw();
125 bool check(std::string name) {
126 normalizeFrameName(name);
129 std::lock_guard<std::mutex> lock(_mutex);
130 auto it = _references.find(name);
131 if (it != _references.end()) {
132 if (it->second > 0) {
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>>
148 std::vector<Optional<Eigen::Isometry3d>,
149 Eigen::aligned_allocator<Optional<Eigen::Isometry3d>>>
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;
159 std::unique_lock<std::mutex> lock(_mutex);
160 _index_to_name.clear();
161 _name_to_index_map.clear();
162 _connections.clear();
169 _redraw_emitted =
false;
172 size_t nameToIndexCreate(std::string name) {
173 normalizeFrameName(name);
175 auto it = _name_to_index_map.find(name);
176 if (it != _name_to_index_map.end()) {
180 _name_to_index_map[name] = _index_to_name.size();
181 _index_to_name.push_back(name);
183 auto it = _name_to_index_map.find(name);
184 if (it != _name_to_index_map.end()) {
188 throw std::runtime_error(
"");
191 ssize_t tryNameToIndex(std::string name) {
192 normalizeFrameName(name);
194 auto it = _name_to_index_map.find(name);
195 if (it != _name_to_index_map.end()) {
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;
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])) {
218 if ((_connections[parent][child].matrix() != transform.matrix()) &&
219 ((parent < _used.size() && _used[parent]) &&
220 (child < _used.size() && _used[child]))) {
223 _connections[parent][child] = transform;
224 _connections[child][parent] = transform_inverse;
228 if (!_redraw_emitted) {
229 _redraw_emitted =
true;
231 GlobalEvents::instance()->redraw();
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);
245 _parents.resize(_poses.size(), -1);
247 _used.resize(_poses.size(), 0);
248 _poses[root] = Eigen::Isometry3d::Identity();
250 _current.push_back(root);
252 _visited.resize(_index_to_name.size(), 0);
254 while (!_current.empty()) {
256 for (
size_t curr : _current) {
257 for (
auto &conn : _connections[curr]) {
258 if (!_visited[conn.first]) {
260 _visited[conn.first] =
true;
261 _poses[conn.first] = *_poses[curr] * conn.second;
262 _parents[conn.first] = curr;
263 _next.emplace_back(conn.first);
271 auto manager = FrameManager::instance();
272 std::lock_guard<std::mutex> lock(manager->_mutex);
273 for (
auto &p : manager->_references) {
275 ssize_t i = tryNameToIndex(p.first);
276 while (i >= 0 && !_used[i]) {
284 for (
size_t i = 0; i < _used.size(); i++) {
286 LOG_DEBUG(i <<
" " << _index_to_name[i] <<
" " << (
int)_used[i]);
291 LOG_WARN_THROTTLE(1.0,
"no connections from base frame: " << root_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];
305 std::vector<std::string> list() {
306 std::unordered_set<size_t> indices;
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);
316 std::vector<std::string> ret;
317 for (
auto i : indices) {
318 ret.push_back(_index_to_name[i]);
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) {
329 if (
auto msg = message->instantiate<tf::tfMessage>()) {
330 for (
auto &tf : msg->transforms) {
334 if (
auto msg = message->instantiate<geometry_msgs::TransformStamped>()) {
340 Transformer::Transformer(
bool subscribe) {
341 LOG_DEBUG(
"Transformer ctor");
342 _data = std::make_shared<Data>();
344 auto _data = this->_data;
345 std::thread([_data]() {
346 if (_data->_subscribers.empty()) {
348 auto topic =
"/tf_static";
349 auto *data = _data.get();
350 auto subscriber = std::make_shared<Subscriber<Message>>(
352 [data](
const std::shared_ptr<const Message> &message) {
353 PROFILER(
"Transformer");
357 subscriber->topic()->connected.connect(_data,
358 [data]() { data->clear(); });
359 _data->_subscribers.push_back(subscriber);
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>(
369 const std::shared_ptr<const geometry_msgs::TransformStamped>
371 if (
auto d = data.lock()) {
372 PROFILER(
"Transformer");
376 subscriber->addListener(listener);
377 _data->_subscribers.push_back(listener);
385 Transformer::~Transformer() { LOG_DEBUG(
"Transformer dtor"); }
387 void Transformer::clear() { _data->clear(); }
389 void Transformer::update(
const std::string &root) {
394 void Transformer::push(
const std::shared_ptr<const Message> &message) {
395 _data->push(message);
398 std::vector<std::string> Transformer::list() {
return _data->list(); }
408 Frame::Frame(
const std::string &name) : _name(name) {}
410 Frame::Frame(
const Frame &other) { _name = other._name; }
413 if (other._name != _name) {
415 FrameManager::instance()->count(other._name, +1);
416 FrameManager::instance()->count(_name, -1);
423 void Frame::name(
const std::string &name) {
426 FrameManager::instance()->count(name, +1);
427 FrameManager::instance()->count(_name, -1);
435 FrameManager::instance()->count(_name, -1);
440 Frame::pose(
const std::shared_ptr<Transformer> &transformer) {
443 FrameManager::instance()->count(_name, +1);
445 return transformer->_data->lookup(_name);
450 attributes->list = [](
const Property &property) {
451 return LockScope()->document()->display()->transformer->list();