00001 #ifndef OROCOS_RTT_TF_COMPONENT_HPP 00002 #define OROCOS_RTT_TF_COMPONENT_HPP 00003 00004 #include <rtt/RTT.hpp> 00005 #include <tf/tf.h> 00006 #include <tf/tfMessage.h> 00007 00008 namespace rtt_tf 00009 { 00010 00011 class RTT_TF: public RTT::TaskContext 00012 { 00013 static const int DEFAULT_BUFFER_SIZE = 100; 00014 00015 boost::shared_ptr<tf::Transformer> m_transformer; 00016 bool prop_interpolating; 00017 double prop_cache_time; 00018 double prop_buffer_size; 00019 00020 RTT::InputPort<tf::tfMessage> port_tf_in; 00021 00022 geometry_msgs::TransformStamped lookupTransform(const std::string& parent, 00023 const std::string& child); 00024 00025 public: 00026 RTT_TF(string const& name); 00027 00028 bool configureHook(); 00029 00030 bool startHook(){return true;}; 00031 00032 void updateHook(); 00033 00034 void stopHook(){}; 00035 00036 void cleanupHook(){}; 00037 }; 00038 }//namespace rtt_tf 00039 #endif