tf2_client.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
2 #include <tf2/buffer_core.h>
4 #include <tf2_ros/buffer.h>
7 
8 namespace tf2_client {
9 
11  static std::mutex mtx;
12  std::lock_guard<std::mutex> lck(mtx);
13  static BufferPtr buffer;
14  typedef std::unique_ptr<tf2_ros::TransformListener> ListenerPtr;
15  static ListenerPtr listener;
16  if (!buffer) {
17  std::string server;
18  pnh.param("tf_server", server, server);
19  if (!server.empty()) {
20  double check_frequency(10.0);
21  pnh.param("tf_check_frequency", check_frequency, check_frequency);
22  double timeout_padding(2.0);
23  pnh.param("tf_timeout_padding", timeout_padding, timeout_padding);
24 
25  buffer = std::make_shared<tf2_ros::BufferClient>(server, check_frequency, ros::Duration(timeout_padding));
26  ROS_INFO("Using tf buffer client (server %s, timeout padding %.3g s).", server.c_str(), timeout_padding);
27  } else {
28  double cache_time(tf2::BufferCore::DEFAULT_CACHE_TIME);
29  pnh.param("tf_cache_time", cache_time, cache_time);
30 
31  buffer = std::make_shared<tf2_ros::Buffer>(ros::Duration(cache_time));
32  listener = std::make_unique<tf2_ros::TransformListener>(dynamic_cast<tf2_ros::Buffer &>(*buffer), nh, true);
33  ROS_INFO("Using local tf buffer (cache %.3g s).", cache_time);
34  }
35  }
36  return buffer;
37 }
38 
39 } // namespace
BufferPtr get_buffer(ros::NodeHandle &nh, ros::NodeHandle &pnh)
Definition: tf2_client.cpp:10
bool param(const std::string &param_name, T &param_val, const T &default_val) const
#define ROS_INFO(...)
static const int DEFAULT_CACHE_TIME
std::shared_ptr< tf2_ros::BufferInterface > BufferPtr
Definition: tf2_client.h:7


tf2_client
Author(s): Tomas Petricek
autogenerated on Sat May 27 2023 02:41:41