#include <rtt_tf-component.hpp>
Public Member Functions | |
void | cleanupHook () |
bool | configureHook () |
RTT_TF (std::string const &name) | |
bool | startHook () |
void | stopHook () |
void | updateHook () |
Private Member Functions | |
void | addTFOperations (RTT::Service::shared_ptr service) |
void | broadcastTransform (const geometry_msgs::TransformStamped &tform) |
void | broadcastTransforms (const std::vector< geometry_msgs::TransformStamped > &tforms) |
bool | canTransform (const std::string &parent, const std::string &child) |
geometry_msgs::TransformStamped | lookupTransform (const std::string &parent, const std::string &child) |
geometry_msgs::TransformStamped | lookupTransformAtTime (const std::string &parent, const std::string &child, const ros::Time &common_time) |
Private Attributes | |
boost::shared_ptr < tf::Transformer > | m_transformer |
RTT::InputPort< tf::tfMessage > | port_tf_in |
RTT::OutputPort< tf::tfMessage > | port_tf_out |
double | prop_buffer_size |
double | prop_cache_time |
std::string | prop_tf_prefix |
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 | ( | std::string const & | name | ) |
Definition at line 58 of file rtt_tf-component.cpp.
void rtt_tf::RTT_TF::addTFOperations | ( | RTT::Service::shared_ptr | service | ) | [private] |
Definition at line 74 of file rtt_tf-component.cpp.
void rtt_tf::RTT_TF::broadcastTransform | ( | const geometry_msgs::TransformStamped & | tform | ) | [private] |
Definition at line 202 of file rtt_tf-component.cpp.
void rtt_tf::RTT_TF::broadcastTransforms | ( | const std::vector< geometry_msgs::TransformStamped > & | tforms | ) | [private] |
Definition at line 216 of file rtt_tf-component.cpp.
bool rtt_tf::RTT_TF::canTransform | ( | const std::string & | parent, |
const std::string & | child | ||
) | [private] |
Definition at line 180 of file rtt_tf-component.cpp.
void rtt_tf::RTT_TF::cleanupHook | ( | ) | [inline, virtual] |
Reimplemented from RTT::base::TaskCore.
Definition at line 55 of file rtt_tf-component.hpp.
bool rtt_tf::RTT_TF::configureHook | ( | ) | [virtual] |
Reimplemented from RTT::base::TaskCore.
Definition at line 101 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 167 of file rtt_tf-component.cpp.
geometry_msgs::TransformStamped rtt_tf::RTT_TF::lookupTransformAtTime | ( | const std::string & | parent, |
const std::string & | child, | ||
const ros::Time & | common_time | ||
) | [private] |
Definition at line 190 of file rtt_tf-component.cpp.
bool rtt_tf::RTT_TF::startHook | ( | ) | [inline, virtual] |
Reimplemented from RTT::base::TaskCore.
Definition at line 49 of file rtt_tf-component.hpp.
void rtt_tf::RTT_TF::stopHook | ( | ) | [inline, virtual] |
Reimplemented from RTT::base::TaskCore.
Definition at line 53 of file rtt_tf-component.hpp.
void rtt_tf::RTT_TF::updateHook | ( | ) | [virtual] |
Reimplemented from RTT::base::TaskCore.
Definition at line 123 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.
RTT::OutputPort<tf::tfMessage> rtt_tf::RTT_TF::port_tf_out [private] |
Definition at line 21 of file rtt_tf-component.hpp.
double rtt_tf::RTT_TF::prop_buffer_size [private] |
Definition at line 17 of file rtt_tf-component.hpp.
double rtt_tf::RTT_TF::prop_cache_time [private] |
Definition at line 16 of file rtt_tf-component.hpp.
std::string rtt_tf::RTT_TF::prop_tf_prefix [private] |
Definition at line 18 of file rtt_tf-component.hpp.