#include <rtt_tf-component.hpp>
Public Member Functions | |
void | cleanupHook () |
bool | configureHook () |
RTT_TF (string const &name) | |
bool | startHook () |
void | stopHook () |
void | updateHook () |
Private Member Functions | |
geometry_msgs::TransformStamped | lookupTransform (const std::string &parent, const std::string &child) |
Private Attributes | |
boost::shared_ptr < tf::Transformer > | m_transformer |
RTT::InputPort< tf::tfMessage > | port_tf_in |
double | prop_buffer_size |
double | prop_cache_time |
bool | prop_interpolating |
Static Private Attributes | |
static const int | DEFAULT_BUFFER_SIZE = 100 |
Definition at line 11 of file rtt_tf-component.hpp.
rtt_tf::RTT_TF::RTT_TF | ( | string const & | name | ) |
Definition at line 54 of file rtt_tf-component.cpp.
void rtt_tf::RTT_TF::cleanupHook | ( | ) | [inline] |
Definition at line 36 of file rtt_tf-component.hpp.
bool rtt_tf::RTT_TF::configureHook | ( | ) |
Definition at line 70 of file rtt_tf-component.cpp.
geometry_msgs::TransformStamped rtt_tf::RTT_TF::lookupTransform | ( | const std::string & | parent, | |
const std::string & | child | |||
) | [private] |
Definition at line 133 of file rtt_tf-component.cpp.
bool rtt_tf::RTT_TF::startHook | ( | ) | [inline] |
Definition at line 30 of file rtt_tf-component.hpp.
void rtt_tf::RTT_TF::stopHook | ( | ) | [inline] |
Definition at line 34 of file rtt_tf-component.hpp.
void rtt_tf::RTT_TF::updateHook | ( | ) |
Definition at line 83 of file rtt_tf-component.cpp.
const int rtt_tf::RTT_TF::DEFAULT_BUFFER_SIZE = 100 [static, private] |
Definition at line 13 of file rtt_tf-component.hpp.
boost::shared_ptr<tf::Transformer> rtt_tf::RTT_TF::m_transformer [private] |
Definition at line 15 of file rtt_tf-component.hpp.
RTT::InputPort<tf::tfMessage> rtt_tf::RTT_TF::port_tf_in [private] |
Definition at line 20 of file rtt_tf-component.hpp.
double rtt_tf::RTT_TF::prop_buffer_size [private] |
Definition at line 18 of file rtt_tf-component.hpp.
double rtt_tf::RTT_TF::prop_cache_time [private] |
Definition at line 17 of file rtt_tf-component.hpp.
bool rtt_tf::RTT_TF::prop_interpolating [private] |
Definition at line 16 of file rtt_tf-component.hpp.