Class for using the TF component from C++. More...
#include <tf_interface.h>
Public Member Functions | |
bool | ready () |
Check if the operations are ready. | |
TFInterface (RTT::TaskContext *owner) | |
Add interfaces to a given taskcontext. | |
Public Attributes | |
RTT::OperationCaller< void(const geometry_msgs::TransformStamped &)> | broadcastTransform |
RTT::OperationCaller< void(const std::vector < geometry_msgs::TransformStamped > &)> | broadcastTransforms |
RTT::OperationCaller< bool(const std::string &, const std::string &)> | canTransform |
RTT::OperationCaller < geometry_msgs::TransformStamped(const std::string &, const std::string &)> | lookupTransform |
RTT::OperationCaller < geometry_msgs::TransformStamped(const std::string &, const std::string &, const ros::Time &)> | lookupTransformAtTime |
Class for using the TF component from C++.
Definition at line 13 of file tf_interface.h.
rtt_tf::TFInterface::TFInterface | ( | RTT::TaskContext * | owner | ) | [inline] |
Add interfaces to a given taskcontext.
Definition at line 16 of file tf_interface.h.
bool rtt_tf::TFInterface::ready | ( | ) | [inline] |
Check if the operations are ready.
Definition at line 31 of file tf_interface.h.
RTT::OperationCaller<void(const geometry_msgs::TransformStamped&)> rtt_tf::TFInterface::broadcastTransform |
Definition at line 42 of file tf_interface.h.
RTT::OperationCaller<void(const std::vector<geometry_msgs::TransformStamped>&)> rtt_tf::TFInterface::broadcastTransforms |
Definition at line 43 of file tf_interface.h.
RTT::OperationCaller<bool(const std::string&, const std::string&)> rtt_tf::TFInterface::canTransform |
Definition at line 44 of file tf_interface.h.
RTT::OperationCaller<geometry_msgs::TransformStamped(const std::string&, const std::string&)> rtt_tf::TFInterface::lookupTransform |
Definition at line 40 of file tf_interface.h.
RTT::OperationCaller<geometry_msgs::TransformStamped(const std::string&, const std::string&, const ros::Time&)> rtt_tf::TFInterface::lookupTransformAtTime |
Definition at line 41 of file tf_interface.h.