1 #ifndef OROCOS_RTT_TF_COMPONENT_HPP 2 #define OROCOS_RTT_TF_COMPONENT_HPP 5 #include <tf2_msgs/TFMessage.h> 9 #include <boost/shared_ptr.hpp> 30 std::map<std::pair<std::string, std::string>, OutputPortGeometryTransfromStampedPtr>
ports_trackers;
35 tf2_msgs::TFMessage& msg,
40 const std::string& target,
41 const std::string& source)
const;
44 const std::string& target,
45 const std::string& source)
const;
48 const std::string& target,
49 const std::string& source,
53 const std::string& target,
54 const std::string& source)
const;
57 const std::string& target,
58 const std::string& source,
62 const geometry_msgs::TransformStamped &tform);
65 const std::vector<geometry_msgs::TransformStamped> &tforms);
68 const geometry_msgs::TransformStamped &tform);
71 const std::vector<geometry_msgs::TransformStamped> &tforms);
76 const std::string& target,
77 const std::string& source);
82 RTT_TF(std::string
const& name);
bool canTransform(const std::string &target, const std::string &source) const
void addTFOperations(RTT::Service::shared_ptr service)
geometry_msgs::TransformStamped lookupTransform(const std::string &target, const std::string &source) const
boost::shared_ptr< tf2_ros::TransformListener > TransformListenerPtr
boost::shared_ptr< tf2::BufferCore > BufferCorePtr
ros::Time getLatestCommonTime(const std::string &target, const std::string &source) const
TransformListenerPtr transform_listener
RTT::OutputPort< tf2_msgs::TFMessage > port_tf_static_out
std::map< std::pair< std::string, std::string >, OutputPortGeometryTransfromStampedPtr > ports_trackers
bool subscribeTransfrom(const std::string &target, const std::string &source)
static const int DEFAULT_BUFFER_SIZE
bool canTransformAtTime(const std::string &target, const std::string &source, const ros::Time &common_time) const
RTT::OutputPort< tf2_msgs::TFMessage > port_tf_out
void broadcastTransform(const geometry_msgs::TransformStamped &tform)
RTT::InputPort< tf2_msgs::TFMessage > port_tf_static_in
RTT::InputPort< tf2_msgs::TFMessage > port_tf_in
void internalUpdate(tf2_msgs::TFMessage &msg, RTT::InputPort< tf2_msgs::TFMessage > &port, bool is_static)
void broadcastTransforms(const std::vector< geometry_msgs::TransformStamped > &tforms)
void broadcastStaticTransforms(const std::vector< geometry_msgs::TransformStamped > &tforms)
BufferCorePtr buffer_core
void broadcastStaticTransform(const geometry_msgs::TransformStamped &tform)
RTT_TF(std::string const &name)
geometry_msgs::TransformStamped lookupTransformAtTime(const std::string &target, const std::string &source, const ros::Time &common_time) const
std::string prop_tf_prefix
boost::shared_ptr< RTT::OutputPort< geometry_msgs::TransformStamped > > OutputPortGeometryTransfromStampedPtr