topic_with_transform.h
Go to the documentation of this file.
1 
8 #ifndef __TOPIC_WITH_TRANSFORM_H
9 #define __TOPIC_WITH_TRANSFORM_H
10 
11 #include <string>
12 #include <vector>
13 #include <memory>
15 #include <tf/message_filter.h>
16 #include <tf/transform_listener.h>
17 #include <boost/shared_ptr.hpp>
18 
23 // TODO: make this class inner
24 template <typename MType>
25 class TopicObserver { // iface
26 public: // methods
28  const tf::StampedTransform&) = 0;
29 };
30 
34 // TODO: add scan drop
35 template <typename MsgType>
37  /* NB: wasn't able to implement with TF2 (ROS jade),
38  probably because of deadlock
39  (https://github.com/ros/geometry2/pull/144)
40  Try TF2 with proposed patch.
41  */
42 public: // methods
43  // TODO: copy, move ctrs, dtor
45  const std::string& topic_name,
46  const std::string& target_frame,
47  const double buffer_duration,
48  const double tf_filter_queue_size,
49  const double subscribers_queue_size):
50  FILTER_QUEUE_SZ(tf_filter_queue_size),
51  SUBSCR_QUEUE_SZ(subscribers_queue_size),
52  _target_frame{target_frame},
53  _subscr{nh, topic_name, SUBSCR_QUEUE_SZ},
54  _tf_lsnr{ros::Duration(buffer_duration)},
55  _msg_flt{new tf::MessageFilter<MsgType>{
56  _subscr, _tf_lsnr, _target_frame, FILTER_QUEUE_SZ}} {
58  this);
59  }
60 
65  void subscribe(std::shared_ptr<TopicObserver<MsgType>> obs) {
66  _observers.push_back(obs);
67  }
68 private: // consts
69 
70  const uint32_t FILTER_QUEUE_SZ = 10000; // elems
71  const uint32_t SUBSCR_QUEUE_SZ = 10000; // elems
72 private: // methods
74  tf::StampedTransform transform;
75  std::string msg_frame_id =
77  ros::Time msg_time =
79 
80  try{
81  // NB: using last available msg (time = 0) causes issues
82  // on running with higher rate.
83  _tf_lsnr.lookupTransform(_target_frame, msg_frame_id,
84  msg_time, transform);
85  }
86  catch (tf::TransformException ex){
87  ROS_ERROR("Transform retrieval failed. %s",ex.what());
88  return;
89  }
90 
91  for (auto obs : _observers) {
92  if (auto obs_ptr = obs.lock()) {
93  obs_ptr->handle_transformed_msg(msg, transform);
94  }
95  }
96  }
97 private: // fields
98  std::string _target_frame;
101  std::unique_ptr<tf::MessageFilter<MsgType>> _msg_flt;
102  std::vector<std::weak_ptr<TopicObserver<MsgType>>> _observers;
103 };
104 
105 #endif // macro guard
std::vector< std::weak_ptr< TopicObserver< MsgType > > > _observers
message_filters::Subscriber< MsgType > _subscr
virtual void handle_transformed_msg(const boost::shared_ptr< MType >, const tf::StampedTransform &)=0
tf::TransformListener _tf_lsnr
void subscribe(std::shared_ptr< TopicObserver< MsgType >> obs)
Registers a topic observer to be notified with sensor data.
The base class which subclasses convert laser scan and odometry data ROS structures to internal data ...
std::unique_ptr< tf::MessageFilter< MsgType > > _msg_flt
void transformed_msg_cb(const boost::shared_ptr< MsgType > msg)
TopicWithTransform(ros::NodeHandle nh, const std::string &topic_name, const std::string &target_frame, const double buffer_duration, const double tf_filter_queue_size, const double subscribers_queue_size)
This class synchronizes the transform and odometry.
#define ROS_ERROR(...)
Connection registerCallback(const C &callback)


tiny_slam
Author(s):
autogenerated on Mon Jun 10 2019 15:30:57