This class synchronizes the transform and odometry. More...
#include <topic_with_transform.h>
Public Member Functions | |
void | subscribe (std::shared_ptr< TopicObserver< MsgType >> obs) |
Registers a topic observer to be notified with sensor data. More... | |
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) | |
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 |
const uint32_t | FILTER_QUEUE_SZ = 10000 |
const uint32_t | SUBSCR_QUEUE_SZ = 10000 |
This class synchronizes the transform and odometry.
Definition at line 36 of file topic_with_transform.h.
|
inline |
Definition at line 44 of file topic_with_transform.h.
|
inline |
Registers a topic observer to be notified with sensor data.
obs | Pointer to the TopicObserver. |
Definition at line 65 of file topic_with_transform.h.
|
inlineprivate |
Definition at line 73 of file topic_with_transform.h.
|
private |
Definition at line 101 of file topic_with_transform.h.
|
private |
Definition at line 102 of file topic_with_transform.h.
|
private |
Definition at line 99 of file topic_with_transform.h.
|
private |
Definition at line 98 of file topic_with_transform.h.
|
private |
Definition at line 100 of file topic_with_transform.h.
|
private |
Definition at line 70 of file topic_with_transform.h.
|
private |
Definition at line 71 of file topic_with_transform.h.