tf2.h
Go to the documentation of this file.
1 #pragma once
2 
3 #ifdef ROS2 /**********************************************************************************************************/
4 
5 #define TF2_BUFFER_CTOR_ARGS(nh) nh->get_clock_interface()->get_clock()
6 
7 inline std::unique_ptr<tf2_ros::Buffer> make_tf2_buffer(ensenso::ros::NodeHandle const& nh)
8 {
9  return ensenso::std::make_unique<tf2_ros::Buffer>(TF2_BUFFER_CTOR_ARGS(nh));
10 }
11 
12 inline std::unique_ptr<tf2_ros::TransformBroadcaster> make_tf2_broadcaster(ensenso::ros::NodeHandle const& nh)
13 {
14  return ensenso::std::make_unique<tf2_ros::TransformBroadcaster>(nh->node());
15 }
16 
17 #else /***ROS1*********************************************************************************************************/
18 #define TF2_BUFFER_CTOR_ARGS(nh)
19 
20 inline std::unique_ptr<tf2_ros::Buffer> make_tf2_buffer(ensenso::ros::NodeHandle const& nh)
21 {
22  return ensenso::std::make_unique<tf2_ros::Buffer>();
23 }
24 
25 inline std::unique_ptr<tf2_ros::TransformBroadcaster> make_tf2_broadcaster(ensenso::ros::NodeHandle const& nh)
26 {
27  return ensenso::std::make_unique<tf2_ros::TransformBroadcaster>();
28 }
29 #endif
make_tf2_broadcaster
std::unique_ptr< tf2_ros::TransformBroadcaster > make_tf2_broadcaster(ensenso::ros::NodeHandle const &nh)
Definition: tf2.h:25
ensenso::ros::NodeHandle
::ros::NodeHandle NodeHandle
Definition: node.h:215
make_tf2_buffer
std::unique_ptr< tf2_ros::Buffer > make_tf2_buffer(ensenso::ros::NodeHandle const &nh)
Definition: tf2.h:20
TF2_BUFFER_CTOR_ARGS
#define TF2_BUFFER_CTOR_ARGS(nh)
Definition: tf2.h:18


ensenso_camera
Author(s): Ensenso
autogenerated on Wed Apr 2 2025 02:37:46