Public Member Functions | Private Member Functions | Private Attributes | List of all members
TopicWithTransform< MsgType > Class Template Reference

#include <topic_with_transform.h>

Public Member Functions

void subscribe (std::shared_ptr< TopicObserver< MsgType >> obs)
 
 TopicWithTransform (ros::NodeHandle nh, const std::string &topic_name, const std::string &target_frame, const double buffer_duration=5.0, const uint32_t tf_filter_queue_size=1000, const uint32_t subscribers_queue_size=1000)
 

Private Member Functions

void transformed_msg_cb (const boost::shared_ptr< MsgType > msg)
 

Private Attributes

std::unique_ptr< tf::MessageFilter< MsgType > > _msg_flt
 
std::vector< std::weak_ptr< TopicObserver< MsgType > > > _observers
 
message_filters::Subscriber< MsgType > _subscr
 
std::string _target_frame
 
tf::TransformListener _tf_lsnr
 

Detailed Description

template<typename MsgType>
class TopicWithTransform< MsgType >

Definition at line 22 of file topic_with_transform.h.

Constructor & Destructor Documentation

template<typename MsgType>
TopicWithTransform< MsgType >::TopicWithTransform ( ros::NodeHandle  nh,
const std::string &  topic_name,
const std::string &  target_frame,
const double  buffer_duration = 5.0,
const uint32_t  tf_filter_queue_size = 1000,
const uint32_t  subscribers_queue_size = 1000 
)
inline

Definition at line 30 of file topic_with_transform.h.

Member Function Documentation

template<typename MsgType>
void TopicWithTransform< MsgType >::subscribe ( std::shared_ptr< TopicObserver< MsgType >>  obs)
inline

Definition at line 45 of file topic_with_transform.h.

template<typename MsgType>
void TopicWithTransform< MsgType >::transformed_msg_cb ( const boost::shared_ptr< MsgType >  msg)
inlineprivate

Definition at line 49 of file topic_with_transform.h.

Member Data Documentation

template<typename MsgType>
std::unique_ptr<tf::MessageFilter<MsgType> > TopicWithTransform< MsgType >::_msg_flt
private

Definition at line 77 of file topic_with_transform.h.

template<typename MsgType>
std::vector<std::weak_ptr<TopicObserver<MsgType> > > TopicWithTransform< MsgType >::_observers
private

Definition at line 78 of file topic_with_transform.h.

template<typename MsgType>
message_filters::Subscriber<MsgType> TopicWithTransform< MsgType >::_subscr
private

Definition at line 75 of file topic_with_transform.h.

template<typename MsgType>
std::string TopicWithTransform< MsgType >::_target_frame
private

Definition at line 74 of file topic_with_transform.h.

template<typename MsgType>
tf::TransformListener TopicWithTransform< MsgType >::_tf_lsnr
private

Definition at line 76 of file topic_with_transform.h.


The documentation for this class was generated from the following file:


slam_constructor
Author(s): JetBrains Research, OSLL team
autogenerated on Mon Jun 10 2019 15:08:26