tf2_ros  master
This package contains the ROS bindings for the tf2 library, for both Python and C++.
transform_listener.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
32 #ifndef TF2_ROS__TRANSFORM_LISTENER_H_
33 #define TF2_ROS__TRANSFORM_LISTENER_H_
34 
35 #include <memory>
36 #include <string>
37 #include <thread>
38 #include "tf2_msgs/msg/tf_message.hpp"
39 #include "rclcpp/rclcpp.hpp"
40 
41 #include "tf2_ros/buffer.h"
42 #include "tf2_ros/qos.hpp"
44 
45 namespace tf2_ros
46 {
47 
51 {
52 public:
55  explicit TransformListener(tf2::BufferCore & buffer, bool spin_thread = true);
56 
57  template<class NodeT, class AllocatorT = std::allocator<void>>
59  tf2::BufferCore & buffer,
60  NodeT && node,
61  bool spin_thread = true,
62  const rclcpp::QoS & qos = DynamicListenerQoS(),
63  const rclcpp::QoS & static_qos = StaticListenerQoS(),
64  const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options =
65  rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>())
66  : buffer_(buffer)
67  {
68  init(node, spin_thread, qos, static_qos, options);
69  }
70 
72  virtual ~TransformListener();
73 
74 private:
75  template<class NodeT, class AllocatorT = std::allocator<void>>
76  void init(
77  NodeT && node,
78  bool spin_thread,
79  const rclcpp::QoS & qos,
80  const rclcpp::QoS & static_qos,
81  const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options =
82  rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>())
83  {
84  using callback_t = std::function<void(tf2_msgs::msg::TFMessage::SharedPtr)>;
85  callback_t cb = std::bind(&TransformListener::subscription_callback, this, std::placeholders::_1, false);
86  callback_t static_cb = std::bind(&TransformListener::subscription_callback, this, std::placeholders::_1, true);
87 
88  message_subscription_tf_ = rclcpp::create_subscription<tf2_msgs::msg::TFMessage>(
89  node,
90  "/tf",
91  qos,
92  std::move(cb),
93  options);
94  message_subscription_tf_static_ = rclcpp::create_subscription<tf2_msgs::msg::TFMessage>(
95  node,
96  "/tf_static",
97  static_qos,
98  std::move(static_cb),
99  options);
100 
101  if (spin_thread) {
102  initThread(node->get_node_base_interface());
103  }
104  }
105 
107  void initThread(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface);
108 
111  void subscription_callback(tf2_msgs::msg::TFMessage::SharedPtr msg, bool is_static);
112 
113  // ros::CallbackQueue tf_message_callback_queue_;
114  using thread_ptr =
116  thread_ptr dedicated_listener_thread_;
117 
118  rclcpp::Node::SharedPtr optional_default_node_ = nullptr;
119  rclcpp::Subscription<tf2_msgs::msg::TFMessage>::SharedPtr message_subscription_tf_;
120  rclcpp::Subscription<tf2_msgs::msg::TFMessage>::SharedPtr message_subscription_tf_static_;
121  tf2::BufferCore & buffer_;
122  tf2::TimePoint last_update_;
123 };
124 } // namespace tf2_ros
125 
126 #endif // TF2_ROS__TRANSFORM_LISTENER_H_
std::bind
T bind(T... args)
std::move
T move(T... args)
std::function
qos.hpp
tf2_ros::TransformListener
This class provides an easy way to request and receive coordinate frame transform information.
Definition: transform_listener.h:50
std::thread
tf2_ros
Definition: async_buffer_interface.h:41
tf2_ros::TransformListener::TransformListener
TF2_ROS_PUBLIC TransformListener(tf2::BufferCore &buffer, bool spin_thread=true)
Constructor for transform listener.
tf2_ros::DynamicListenerQoS
Definition: qos.hpp:39
TF2_ROS_PUBLIC
#define TF2_ROS_PUBLIC
Definition: visibility_control.h:58
tf2_ros::TransformListener::TransformListener
TransformListener(tf2::BufferCore &buffer, NodeT &&node, bool spin_thread=true, const rclcpp::QoS &qos=DynamicListenerQoS(), const rclcpp::QoS &static_qos=StaticListenerQoS(), const rclcpp::SubscriptionOptionsWithAllocator< AllocatorT > &options=rclcpp::SubscriptionOptionsWithAllocator< AllocatorT >())
Definition: transform_listener.h:58
tf2_ros::TransformListener::~TransformListener
virtual TF2_ROS_PUBLIC ~TransformListener()
buffer.h
visibility_control.h
tf2_ros::StaticListenerQoS
Definition: qos.hpp:51
std::unique_ptr