8 #ifndef __TOPIC_WITH_TRANSFORM_H 9 #define __TOPIC_WITH_TRANSFORM_H 17 #include <boost/shared_ptr.hpp> 24 template <
typename MType>
35 template <
typename MsgType>
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},
56 _subscr, _tf_lsnr, _target_frame, FILTER_QUEUE_SZ}} {
66 _observers.push_back(obs);
70 const uint32_t FILTER_QUEUE_SZ = 10000;
71 const uint32_t SUBSCR_QUEUE_SZ = 10000;
75 std::string msg_frame_id =
83 _tf_lsnr.lookupTransform(_target_frame, msg_frame_id,
87 ROS_ERROR(
"Transform retrieval failed. %s",ex.what());
91 for (
auto obs : _observers) {
92 if (
auto obs_ptr = obs.lock()) {
93 obs_ptr->handle_transformed_msg(msg, transform);
101 std::unique_ptr<tf::MessageFilter<MsgType>>
_msg_flt;
102 std::vector<std::weak_ptr<TopicObserver<MsgType>>>
_observers;
105 #endif // macro guard
virtual void handle_transformed_msg(const boost::shared_ptr< MType >, const tf::StampedTransform &)=0
The base class which subclasses convert laser scan and odometry data ROS structures to internal data ...
Connection registerCallback(const C &callback)