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

#include <bag_topic_with_transform.h>

Public Member Functions

 BagTopicWithTransform (const std::string &bag_fname, const std::string &topic_name, const std::string &tf_topic_name, const std::string &target_frame)
 
 BagTopicWithTransform (const BagTopicWithTransform &)=delete
 
 BagTopicWithTransform (BagTopicWithTransform &&)=delete
 
bool extract_next_msg ()
 
const auto & msg () const
 
BagTopicWithTransformoperator= (const BagTopicWithTransform &)=delete
 
BagTopicWithTransformoperator= (BagTopicWithTransform &&)=delete
 
void set_tf_ignores (const Transforms &tf_ignores)
 
auto timestamp () const
 
const auto & transform () const
 
 ~BagTopicWithTransform ()
 

Protected Types

using Transforms = std::unordered_map< std::string, std::vector< std::string >>
 
using vstr = std::vector< std::string >
 

Private Member Functions

bool has_synced_msg ()
 
bool should_skip_tf_transform (const geometry_msgs::TransformStamped &t)
 

Private Attributes

rosbag::Bag _bag
 
boost::shared_ptr< MsgType > _msg
 
std::queue< boost::shared_ptr< MsgType > > _msg_cache
 
std::string _target_frame
 
tf::Transformer _tf_cache
 
Transforms _tf_ignores
 
std::string _tf_topic_name
 
std::string _topic_name
 
tf::StampedTransform _transform
 
rosbag::View _view
 
rosbag::View::const_iterator _view_iter
 

Detailed Description

template<typename MsgType>
class BagTopicWithTransform< MsgType >

Definition at line 19 of file bag_topic_with_transform.h.

Member Typedef Documentation

template<typename MsgType >
using BagTopicWithTransform< MsgType >::Transforms = std::unordered_map<std::string, std::vector<std::string>>
protected

Definition at line 22 of file bag_topic_with_transform.h.

template<typename MsgType >
using BagTopicWithTransform< MsgType >::vstr = std::vector<std::string>
protected

Definition at line 21 of file bag_topic_with_transform.h.

Constructor & Destructor Documentation

template<typename MsgType >
BagTopicWithTransform< MsgType >::BagTopicWithTransform ( const std::string &  bag_fname,
const std::string &  topic_name,
const std::string &  tf_topic_name,
const std::string &  target_frame 
)
inline

Definition at line 24 of file bag_topic_with_transform.h.

template<typename MsgType >
BagTopicWithTransform< MsgType >::~BagTopicWithTransform ( )
inline

Definition at line 35 of file bag_topic_with_transform.h.

template<typename MsgType >
BagTopicWithTransform< MsgType >::BagTopicWithTransform ( const BagTopicWithTransform< MsgType > &  )
delete
template<typename MsgType >
BagTopicWithTransform< MsgType >::BagTopicWithTransform ( BagTopicWithTransform< MsgType > &&  )
delete

Member Function Documentation

template<typename MsgType >
bool BagTopicWithTransform< MsgType >::extract_next_msg ( )
inline

Definition at line 48 of file bag_topic_with_transform.h.

template<typename MsgType >
bool BagTopicWithTransform< MsgType >::has_synced_msg ( )
inlineprivate

Definition at line 88 of file bag_topic_with_transform.h.

template<typename MsgType >
const auto& BagTopicWithTransform< MsgType >::msg ( ) const
inline

Definition at line 71 of file bag_topic_with_transform.h.

template<typename MsgType >
BagTopicWithTransform& BagTopicWithTransform< MsgType >::operator= ( const BagTopicWithTransform< MsgType > &  )
delete
template<typename MsgType >
BagTopicWithTransform& BagTopicWithTransform< MsgType >::operator= ( BagTopicWithTransform< MsgType > &&  )
delete
template<typename MsgType >
void BagTopicWithTransform< MsgType >::set_tf_ignores ( const Transforms tf_ignores)
inline

Definition at line 44 of file bag_topic_with_transform.h.

template<typename MsgType >
bool BagTopicWithTransform< MsgType >::should_skip_tf_transform ( const geometry_msgs::TransformStamped &  t)
inlineprivate

Definition at line 79 of file bag_topic_with_transform.h.

template<typename MsgType >
auto BagTopicWithTransform< MsgType >::timestamp ( ) const
inline

Definition at line 73 of file bag_topic_with_transform.h.

template<typename MsgType >
const auto& BagTopicWithTransform< MsgType >::transform ( ) const
inline

Definition at line 72 of file bag_topic_with_transform.h.

Member Data Documentation

template<typename MsgType >
rosbag::Bag BagTopicWithTransform< MsgType >::_bag
private

Definition at line 123 of file bag_topic_with_transform.h.

template<typename MsgType >
boost::shared_ptr<MsgType> BagTopicWithTransform< MsgType >::_msg
private

Definition at line 131 of file bag_topic_with_transform.h.

template<typename MsgType >
std::queue<boost::shared_ptr<MsgType> > BagTopicWithTransform< MsgType >::_msg_cache
private

Definition at line 129 of file bag_topic_with_transform.h.

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

Definition at line 122 of file bag_topic_with_transform.h.

template<typename MsgType >
tf::Transformer BagTopicWithTransform< MsgType >::_tf_cache
private

Definition at line 128 of file bag_topic_with_transform.h.

template<typename MsgType >
Transforms BagTopicWithTransform< MsgType >::_tf_ignores
private

Definition at line 127 of file bag_topic_with_transform.h.

template<typename MsgType >
std::string BagTopicWithTransform< MsgType >::_tf_topic_name
private

Definition at line 122 of file bag_topic_with_transform.h.

template<typename MsgType >
std::string BagTopicWithTransform< MsgType >::_topic_name
private

Definition at line 122 of file bag_topic_with_transform.h.

template<typename MsgType >
tf::StampedTransform BagTopicWithTransform< MsgType >::_transform
private

Definition at line 132 of file bag_topic_with_transform.h.

template<typename MsgType >
rosbag::View BagTopicWithTransform< MsgType >::_view
private

Definition at line 124 of file bag_topic_with_transform.h.

template<typename MsgType >
rosbag::View::const_iterator BagTopicWithTransform< MsgType >::_view_iter
private

Definition at line 125 of file bag_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