659.30 TransformListener의 rclcpp 초기화

1. 개요

tf2_ros::TransformListener를 C++ 클라이언트 라이브러리 rclcpp에서 초기화하기 위해서는 tf2_ros::Buffer 객체를 먼저 생성하고, 이를 TransformListener에 전달하여야 한다. 초기화 과정에서의 선택 사항으로는 캐시 기간(cache duration), 전용 스레드(spin thread) 사용 여부, 콜백 그룹(callback group) 지정 등이 있다. 본 절에서는 TransformListenerrclcpp 기반 초기화 과정을 다양한 시나리오별로 상세히 기술한다.

2. 필수 헤더 파일 및 의존성

2.1 헤더 파일

#include <rclcpp/rclcpp.hpp>
#include <tf2_ros/transform_listener.h>
#include <tf2_ros/buffer.h>
#include <geometry_msgs/msg/transform_stamped.hpp>

2.2 package.xml

<depend>rclcpp</depend>
<depend>tf2_ros</depend>
<depend>tf2</depend>
<depend>geometry_msgs</depend>

2.3 CMakeLists.txt

find_package(rclcpp REQUIRED)
find_package(tf2_ros REQUIRED)
find_package(tf2 REQUIRED)
find_package(geometry_msgs REQUIRED)

add_executable(tf_listener_node src/tf_listener_node.cpp)
ament_target_dependencies(tf_listener_node
  rclcpp
  tf2_ros
  tf2
  geometry_msgs
)

3. Buffer 초기화

3.1 기본 초기화

tf2_ros::Buffer는 노드의 시계(clock)를 인자로 받아 생성된다.

tf_buffer_ = std::make_unique<tf2_ros::Buffer>(this->get_clock());

this->get_clock()은 노드에 바인딩된 시계 객체를 반환한다. use_sim_time 파라미터가 true로 설정된 경우, 시뮬레이션 시간이 자동으로 반영된다.

3.2 캐시 기간 지정

Buffer의 생성자는 캐시 기간을 선택적으로 받는다.

// 기본값: 10초
tf_buffer_ = std::make_unique<tf2_ros::Buffer>(this->get_clock());

// 캐시 기간 30초 지정
tf_buffer_ = std::make_unique<tf2_ros::Buffer>(
  this->get_clock(), tf2::Duration(std::chrono::seconds(30)));

캐시 기간은 동적 변환이 Buffer 내에 유지되는 최대 시간이다. 이 기간을 초과한 변환은 자동으로 삭제된다. 정적 변환은 캐시 기간과 무관하게 무한히 유지된다.

캐시 기간적합한 용도
5초메모리 제약이 있는 임베디드 시스템
10초 (기본)일반적인 로봇 시스템
30초 이상과거 시점의 변환을 빈번히 조회하는 응용

4. TransformListener 초기화 패턴

4.1 패턴 1: 기본 초기화 (전용 스레드 사용)

가장 간단하고 일반적인 초기화 패턴이다.

class TFListenerNode : public rclcpp::Node
{
public:
  TFListenerNode()
  : Node("tf_listener_node")
  {
    tf_buffer_ = std::make_unique<tf2_ros::Buffer>(this->get_clock());
    tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);

    timer_ = this->create_wall_timer(
      std::chrono::milliseconds(200),
      std::bind(&TFListenerNode::on_timer, this));
  }

private:
  void on_timer()
  {
    try {
      auto t = tf_buffer_->lookupTransform(
        "map", "base_link", tf2::TimePointZero);
      // 변환 사용
    } catch (const tf2::TransformException & ex) {
      RCLCPP_DEBUG(this->get_logger(), "%s", ex.what());
    }
  }

  std::unique_ptr<tf2_ros::Buffer> tf_buffer_;
  std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
  rclcpp::TimerBase::SharedPtr timer_;
};

이 패턴에서 TransformListener는 기본적으로 전용 콜백 스레드를 생성하여(spin_thread=true), 사용자의 Executor와 독립적으로 변환 메시지를 수신한다.

4.2 패턴 2: 전용 스레드 비활성화

spin_thread=false로 설정하면, TransformListener의 구독 콜백이 사용자의 Executor에 의하여 처리된다.

tf_buffer_ = std::make_unique<tf2_ros::Buffer>(this->get_clock());
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(
  *tf_buffer_, this, false);  // spin_thread = false

이 경우 반드시 rclcpp::spin() 또는 executor.spin()이 호출되어야 변환이 수신된다. 전용 스레드를 사용하지 않으므로 시스템 리소스 사용이 줄어든다.

4.3 패턴 3: 노드 인터페이스 전달

TransformListener의 생성자는 다양한 형태의 노드 인터페이스를 지원한다.

// rclcpp::Node 참조
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(
  *tf_buffer_, this, false);

// rclcpp::Node::SharedPtr
auto node_ptr = this->shared_from_this();
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(
  *tf_buffer_, node_ptr, false);

4.4 패턴 4: 콜백 그룹 지정

TransformListener가 사용하는 구독자의 콜백 그룹을 명시적으로 지정할 수 있다.

auto callback_group = this->create_callback_group(
  rclcpp::CallbackGroupType::MutuallyExclusive);

tf_buffer_ = std::make_unique<tf2_ros::Buffer>(this->get_clock());
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(
  *tf_buffer_,
  this,
  false,  // spin_thread
  rclcpp::QoS(100),  // qos_profile (/tf)
  rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default)),  // static qos
  callback_group);

콜백 그룹을 지정하면 MultiThreadedExecutor 환경에서 변환 수신 콜백의 동시성(concurrency)을 세밀하게 제어할 수 있다.

5. 생명주기 노드에서의 초기화

rclcpp_lifecycle::LifecycleNode를 사용하는 경우, on_configure 콜백에서 BufferTransformListener를 초기화하고, on_cleanup 콜백에서 해제하는 패턴을 따른다.

#include <rclcpp_lifecycle/lifecycle_node.hpp>

class LifecycleTFListener : public rclcpp_lifecycle::LifecycleNode
{
public:
  LifecycleTFListener()
  : rclcpp_lifecycle::LifecycleNode("lifecycle_tf_listener")
  {}

  CallbackReturn on_configure(const rclcpp_lifecycle::State &)
  {
    tf_buffer_ = std::make_unique<tf2_ros::Buffer>(this->get_clock());
    tf_listener_ = std::make_shared<tf2_ros::TransformListener>(
      *tf_buffer_, this->shared_from_this(), false);

    return CallbackReturn::SUCCESS;
  }

  CallbackReturn on_activate(const rclcpp_lifecycle::State &)
  {
    timer_ = this->create_wall_timer(
      std::chrono::milliseconds(200),
      std::bind(&LifecycleTFListener::on_timer, this));
    return CallbackReturn::SUCCESS;
  }

  CallbackReturn on_deactivate(const rclcpp_lifecycle::State &)
  {
    timer_->cancel();
    return CallbackReturn::SUCCESS;
  }

  CallbackReturn on_cleanup(const rclcpp_lifecycle::State &)
  {
    tf_listener_.reset();
    tf_buffer_.reset();
    return CallbackReturn::SUCCESS;
  }

private:
  void on_timer()
  {
    try {
      auto t = tf_buffer_->lookupTransform(
        "map", "base_link", tf2::TimePointZero);
    } catch (const tf2::TransformException & ex) {
      RCLCPP_DEBUG(this->get_logger(), "%s", ex.what());
    }
  }

  using CallbackReturn =
    rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;

  std::unique_ptr<tf2_ros::Buffer> tf_buffer_;
  std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
  rclcpp::TimerBase::SharedPtr timer_;
};

on_configure에서 초기화하면, 노드가 CONFIGURED 상태에 진입하자마자 변환 수신이 시작된다. 이를 통하여 on_activate에서 변환 조회가 즉시 가능하다.

6. Component 노드에서의 초기화

#include <rclcpp_components/register_node_macro.hpp>

class TFListenerComponent : public rclcpp::Node
{
public:
  explicit TFListenerComponent(const rclcpp::NodeOptions & options)
  : Node("tf_listener_component", options)
  {
    tf_buffer_ = std::make_unique<tf2_ros::Buffer>(this->get_clock());
    tf_listener_ = std::make_shared<tf2_ros::TransformListener>(
      *tf_buffer_, this, false);

    timer_ = this->create_wall_timer(
      std::chrono::milliseconds(200),
      std::bind(&TFListenerComponent::on_timer, this));
  }

private:
  void on_timer()
  {
    // 변환 조회
  }

  std::unique_ptr<tf2_ros::Buffer> tf_buffer_;
  std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
  rclcpp::TimerBase::SharedPtr timer_;
};

RCLCPP_COMPONENTS_REGISTER_NODE(TFListenerComponent)

Component 노드에서는 spin_thread=false를 사용하는 것이 권장된다. Component 노드는 ComposableNodeContainer의 Executor에 의하여 구동되므로, 별도의 전용 스레드를 생성하면 리소스가 불필요하게 소모된다.

7. 멤버 변수 선언 순서

C++에서 클래스 멤버 변수의 소멸 순서는 선언의 역순(reverse order of declaration)을 따른다. TransformListenerBuffer보다 먼저 소멸하도록, 다음의 선언 순서를 유지하여야 한다.

private:
  // Buffer가 먼저 선언되어, 나중에 소멸
  std::unique_ptr<tf2_ros::Buffer> tf_buffer_;
  // Listener가 나중에 선언되어, 먼저 소멸
  std::shared_ptr<tf2_ros::TransformListener> tf_listener_;

이 순서가 역전되면, BufferTransformListener보다 먼저 소멸하여, TransformListener의 콜백에서 이미 소멸한 Buffer에 접근하는 정의되지 않은 동작(undefined behavior)이 발생할 수 있다.

8. 스마트 포인터 선택

포인터 유형적합한 상황
std::unique_ptr<Buffer>Buffer의 소유권이 단일 노드에 한정되는 경우 (대다수)
std::shared_ptr<Buffer>복수의 객체가 Buffer를 공유하는 경우
std::shared_ptr<TransformListener>일반적인 사용 (권장)
std::unique_ptr<TransformListener>소유권 이전이 필요하지 않은 경우

대부분의 사용 사례에서 Bufferstd::unique_ptr로, TransformListenerstd::shared_ptr로 관리하는 것이 적절하다.

9. 초기화 시 흔한 오류

9.1 Buffer 없이 TransformListener 생성

// 잘못된 사용: 임시 Buffer 사용
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(
  tf2_ros::Buffer(this->get_clock()));  // 임시 객체!

임시 Buffer 객체를 참조로 전달하면, 생성자 호출 이후 임시 객체가 소멸하여 댕글링 참조(dangling reference)가 발생한다.

9.2 get_clock() 누락

// 잘못된 사용: 시계 미지정
tf_buffer_ = std::make_unique<tf2_ros::Buffer>();

시계를 지정하지 않으면 use_sim_time 파라미터가 반영되지 않아, 시뮬레이션 환경에서 변환 조회가 실패할 수 있다.

10. 전체 예제

#include <rclcpp/rclcpp.hpp>
#include <tf2_ros/transform_listener.h>
#include <tf2_ros/buffer.h>
#include <geometry_msgs/msg/transform_stamped.hpp>

class RobotPositionTracker : public rclcpp::Node
{
public:
  RobotPositionTracker()
  : Node("robot_position_tracker")
  {
    // Buffer 초기화 (캐시 기간 20초)
    tf_buffer_ = std::make_unique<tf2_ros::Buffer>(
      this->get_clock(),
      tf2::Duration(std::chrono::seconds(20)));

    // TransformListener 초기화 (전용 스레드 사용)
    tf_listener_ = std::make_shared<tf2_ros::TransformListener>(
      *tf_buffer_);

    // 주기적 위치 조회 타이머
    timer_ = this->create_wall_timer(
      std::chrono::milliseconds(100),
      std::bind(&RobotPositionTracker::track_position, this));

    RCLCPP_INFO(this->get_logger(), "Position tracker initialized.");
  }

private:
  void track_position()
  {
    try {
      auto transform = tf_buffer_->lookupTransform(
        "map", "base_link", tf2::TimePointZero);

      double x = transform.transform.translation.x;
      double y = transform.transform.translation.y;
      double z = transform.transform.translation.z;

      RCLCPP_INFO_THROTTLE(this->get_logger(),
        *this->get_clock(), 2000,
        "Robot at: [%.2f, %.2f, %.2f]", x, y, z);
    } catch (const tf2::TransformException & ex) {
      RCLCPP_DEBUG(this->get_logger(), "%s", ex.what());
    }
  }

  std::unique_ptr<tf2_ros::Buffer> tf_buffer_;
  std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
  rclcpp::TimerBase::SharedPtr timer_;
};

int main(int argc, char * argv[])
{
  rclcpp::init(argc, argv);
  rclcpp::spin(std::make_shared<RobotPositionTracker>());
  rclcpp::shutdown();
  return 0;
}

11. 참고 자료

  • ROS2 공식 문서, “Writing a tf2 listener (C++)”, https://docs.ros.org/en/humble/Tutorials/Intermediate/Tf2/Writing-A-Tf2-Listener-Cpp.html
  • tf2_ros API 문서, https://docs.ros2.org/latest/api/tf2_ros/
  • rclcpp API 문서, https://docs.ros2.org/latest/api/rclcpp/
  • ROS2 Humble Hawksbill