#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 |
BagTopicWithTransform & | operator= (const BagTopicWithTransform &)=delete |
BagTopicWithTransform & | operator= (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 |
Definition at line 19 of file bag_topic_with_transform.h.
|
protected |
Definition at line 22 of file bag_topic_with_transform.h.
|
protected |
Definition at line 21 of file bag_topic_with_transform.h.
|
inline |
Definition at line 24 of file bag_topic_with_transform.h.
|
inline |
Definition at line 35 of file bag_topic_with_transform.h.
|
delete |
|
delete |
|
inline |
Definition at line 48 of file bag_topic_with_transform.h.
|
inlineprivate |
Definition at line 88 of file bag_topic_with_transform.h.
|
inline |
Definition at line 71 of file bag_topic_with_transform.h.
|
delete |
|
delete |
|
inline |
Definition at line 44 of file bag_topic_with_transform.h.
|
inlineprivate |
Definition at line 79 of file bag_topic_with_transform.h.
|
inline |
Definition at line 73 of file bag_topic_with_transform.h.
|
inline |
Definition at line 72 of file bag_topic_with_transform.h.
|
private |
Definition at line 123 of file bag_topic_with_transform.h.
|
private |
Definition at line 131 of file bag_topic_with_transform.h.
|
private |
Definition at line 129 of file bag_topic_with_transform.h.
|
private |
Definition at line 122 of file bag_topic_with_transform.h.
|
private |
Definition at line 128 of file bag_topic_with_transform.h.
|
private |
Definition at line 127 of file bag_topic_with_transform.h.
|
private |
Definition at line 122 of file bag_topic_with_transform.h.
|
private |
Definition at line 122 of file bag_topic_with_transform.h.
|
private |
Definition at line 132 of file bag_topic_with_transform.h.
|
private |
Definition at line 124 of file bag_topic_with_transform.h.
|
private |
Definition at line 125 of file bag_topic_with_transform.h.