transform_relay.h
Go to the documentation of this file.
1 
25 #ifndef TF2_RELAY_TRANSFORM_RELAY_H
26 #define TF2_RELAY_TRANSFORM_RELAY_H
27 
28 #include "ros/ros.h"
29 #include "tf2_msgs/TFMessage.h"
30 
32 
33 #include <boost/unordered_map.hpp>
34 
35 #include <string>
36 #include <utility>
37 
38 namespace tf2_relay
39 {
40 
42 {
43 public:
44  TransformRelay(ros::NodeHandle origin, ros::NodeHandle target, double frequency, bool is_static,
46 
47 private:
48  void transformCb(const tf2_msgs::TFMessageConstPtr &transforms);
49 
50  void relayCb();
51 
52  typedef std::pair<std::string, std::string> FrameIdPair;
53 
54  void processTransform(const geometry_msgs::TransformStamped &new_tf);
55 
59 
62 
63  tf2_msgs::TFMessage transform_cache_;
64  boost::unordered_map<FrameIdPair, std::size_t> transform_cache_index_map_;
65 };
66 
67 } // namespace tf2_relay
68 
69 #endif // TF2_RELAY_TRANSFORM_RELAY_H
ros::Subscriber tf_subscriber_
ros::Publisher tf_publisher_
TransformRelay(ros::NodeHandle origin, ros::NodeHandle target, double frequency, bool is_static, message_relay::FrameIdProcessor::ConstPtr frame_id_processor)
boost::unordered_map< FrameIdPair, std::size_t > transform_cache_index_map_
void processTransform(const geometry_msgs::TransformStamped &new_tf)
tf2_msgs::TFMessage transform_cache_
std::pair< std::string, std::string > FrameIdPair
message_relay::FrameIdProcessor::ConstPtr frame_id_processor_
void transformCb(const tf2_msgs::TFMessageConstPtr &transforms)


tf2_relay
Author(s):
autogenerated on Wed Jul 17 2019 03:28:00