11 static std::mutex mtx;
12 std::lock_guard<std::mutex> lck(mtx);
14 typedef std::unique_ptr<tf2_ros::TransformListener> ListenerPtr;
15 static ListenerPtr listener;
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);
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);
29 pnh.
param(
"tf_cache_time", cache_time, cache_time);
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);
BufferPtr get_buffer(ros::NodeHandle &nh, ros::NodeHandle &pnh)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
static const int DEFAULT_CACHE_TIME
std::shared_ptr< tf2_ros::BufferInterface > BufferPtr