ROS 2 통신 구조 이해하기 - C++ 소스코드로 DDS까지 깊이 파헤치기 1편

ROS 2 통신 구조 이해하기 - C++ 소스코드로 DDS까지 깊이 파헤치기 1편

C++ 소스코드 분석과 Fast-RTPS 내부 구조를 통해 리눅스 소켓을 사용하는 ROS 2의 통신 메커니즘 이해하기

1. 서론 : ROS2 통신 개요

이번 글에서는 ROS 2를 접할 때 마주하게 될 통신 구조와 DDS에 대해 자세히 설명하려고 합니다. ROS에 처음 입문하신 분들은 ROS 1과 ROS 2에서 사용되는 다양한 확장자와 추상적인 용어로 가득한 코드들에 당혹스러움을 느낄 수 있습니다.

대부분의 기초 설명 자료들은 노드, 토픽, 서비스, 액션과 같은 기본 개념을 간단히 다룹니다. 그러나 함께 제공되는 C++ 코드 예제와 ROS 2에서 다루는 데이터 교환 방식만으로는 ROS 2가 말하는 ‘DDS 사용과 UDP 기반의 멀티캐스트 통신’이 어떻게 코드와 구조로 구현되는지 쉽게 그려지지 않습니다.

이 글에서는 단순한 데이터 교환 방식의 개념을 넘어서, C++ 코드와 DDS 통신, 그리고 DDS 표준을 따르는 Fast DDS(초기에는 Fast-RTPS로 알려짐)를 통해 리눅스 소켓을 사용한 통신 구조까지 깊이 탐구할 것입니다.

저 역시 이러한 통신 구조를 이해하는 과정에서 여러 어려움을 겪었던 개발자입니다. 이 글이 여러분이 겪을 수 있는 ROS 통신의 개념들 간의 공백을 연결하는 데 도움이 되기를 바랍니다. 여러분이 ROS 2의 통신 구조에 대한 갈증을 해소하는 데 이 글이 작은 기여를 할 수 있기를 기대합니다.

2. ROS2 통신 구조

2.1. ROS2 노드(Node)

ROS 2를 이해하려면 먼저 ‘노드(Node)’의 개념을 정확히 파악해야 합니다. 네트워크 분야에서도 노드라는 용어를 사용하지만, ROS에서의 노드는 조금 다르게 이해해야 합니다. 네트워크의 노드와 마찬가지로, ROS 노드 역시 독립적인 실행 단위로 존재하며, 노드 간에 정보와 데이터를 주고받으며 협력합니다. 하지만 ROS에서는 이 노드를 특정 기능을 수행하기 위해 실행되는 프로그램 또는 프로세스로 정의합니다.

그림1

일반적으로 학교나 강의에서 다루는 프로젝트에서는 노드로 실행되는 프로그램의 수가 적지만, 실무 환경에서는 프로젝트의 규모가 커짐에 따라 하나의 PC에서 다양한 프로세스의 노드가 실행됩니다. 이들 노드는 서로 데이터를 주고받으며, 로봇의 동작을 제어하는 데 필요한 역할을 수행합니다.

예를 들어, 특정 라이다 센서를 구동하고 데이터를 다른 노드로 전달하는 프로세스, 특정 주행 데이터를 받아 로봇의 구동부가 처리할 수 있게 가공하여 동작시키는 프로세스, 구동부의 에러 상태를 알리는 프로세스 등을 각각 하나의 노드로 작성할 수 있습니다.

ROS 2에서는 노드 간 데이터 교환 방식을 설계에 따라 토픽(Topic), 서비스(Service), 액션(Action) 중에서 선택할 수 있습니다. 단순히 데이터를 반복적으로 전송하기만 하면 된다면 메시지(토픽)를 사용하고, 데이터 전달이 잘 이루어졌는지 확인이 필요하다면 서비스를 이용하여 반응까지 확인할 수 있는 설계를 할 수 있습니다.

2.2. ROS 1과 ROS 2의 통신 차이점

ROS 1에서는 TCP 기반의 TCPROS를 통해 노드 간 통신이 이루어졌습니다. 이 방식은 특히 초심자에게 친숙한 방식으로, Host의 IP를 중심으로 프로그램을 구성하고 RosCore를 통해 통신을 관리했습니다. 하지만 이 방식에는 보안 문제가 있습니다. Host의 IP가 노출되면 해당 로봇의 제어권이 쉽게 박탈될 수 있습니다.

ROS 2에서는 이러한 문제를 해결하고 산업용 표준 방식을 채택하기 위해 DDS(Data Distribution Service)를 사용합니다. DDS는 단순한 개념이 아니라, **‘데이터 통신을 위한 미들웨어 API’라고 이해하는 것이 좋습니다.

일부 사람들은 ROS 2를 "통신을 위한 미들웨어 인터페이스"라고 평가하기도 합니다. 이러한 평가가 나오는 이유와 그 배경은 앞으로의 설명을 통해 더욱 명확해질 것입니다.

여러분이 처음 접하게 될 ROS2 C++ 코드를 시작으로 DDS 미들웨어, 그리고 이 미들웨어 내부의 리눅스 소켓 통신이 있음을 살펴볼 겁니다. 미들웨어 소스코드는 ROS2의 Default인 ‘Fast-RTPS’를 채택하도록 할 겁니다. 그럼 ROS2 코드부터 하나씩 살펴보도록 하겠습니다.

3. ROS2 C++ 코드 분석

ROS 2의 통신 구조를 깊이 있게 이해하기 전에, 기본적인 ROS 2 C++ 코드를 먼저 살펴보겠습니다. ROS 2 노드를 구성하고 메시지, 서비스, 액션 등의 통신을 구현하기 위해 기본적으로 필요한 코드는 다음과 같습니다.

#include <rclcpp/rclcpp.hpp>

int main(int argc, char **argv)
{
    rclcpp::init(argc, argv);

    // 노드 생성
    auto node = std::make_shared<rclcpp::Node>("example_node");

    // 스핀 함수 실행 - 노드가 종료될 때까지 계속 실행
    rclcpp::spin(node);

    // 노드 종료 시 실행
    rclcpp::shutdown();
    return 0;
}

이 코드의 핵심은 main 함수 내에 있는 네 가지 필수적인 함수 호출입니다. 각각의 함수는 ROS 2 노드의 초기화, 생성, 실행, 종료를 담당합니다.

3.1. ROS 2 C++ 클라이언트 라이브러리 (rclcpp) 함수 설명

rclcpp::init(argc, argv);

1) ROS 2 시스템을 초기화하는 함수로, 모든 ROS 2 프로그램에서 가장 먼저 호출되어야 합니다.


rclcpp::Node //동적 선언 : std::shared_ptr<rclcpp::Node>

2) ROS 2 노드를 생성하는 클래스입니다. std::shared_ptr<rclcpp::Node> 타입으로 노드를 동적 할당하며, 노드 간 통신을 위해 다양한 기능을 제공합니다.


rclcpp::spin(node);

3) 노드를 실행하고, 메시지 송수신과 콜백 처리를 위해 메인 루프를 시작하는 함수입니다. 노드가 종료될 때까지 계속해서 실행됩니다.


rclcpp::shutdown();

4) ROS 2 노드를 종료하고, 모든 관련 자원을 해제하는 함수입니다. 프로그램 종료 시 반드시 호출됩니다.


init 함수만 타고 들어가다 보면 어느샌가 ‘DDS는 UDP 기반 멀티캐스트로 통신’ 한다는 개념과 함께 노드, 퍼블리셔, 서브스크라이브 등등의 ROS가 아닌데도 익숙한 구조를 마주할 겁니다. 이번에 한 번 구조를 깊이 들어가보도록 하겠습니다.

3.2. rclcpp::init(int argc, char **argv) 함수 파헤치기

#include <rclcpp/rclcpp.hpp>

int main(int argc, char **argv)
{
    rclcpp::init(argc, argv);
}

기존의 C/C++에서 볼 수 있는 main 문과 함께 ROS2를 사용하기 위한 초기화 함수 init()가 있습니다. argc와 argv는 ‘명령행 인수(Command Line Argument)’로 argc(argument count)는 main 함수에 전달된 데이터의 갯수, 전달된 명령은 공백(‘ ‘)을 기준으로 개수를 파악합니다.

argv(argument vector)는 문자열(char* argv[])의 주소를 저장하는 포인터 배열입니다. 그래서 argv[argc]처럼 보시면 될 것 같습니다.

argv[0]에는 “프로그램의 실행 경로”가 들어가며, hello_publisher_node라는 이름으로 빌드한 패키지라면 빌드 후 실행파일이 설치될 “/home/user/ros2_ws/install/lib/hello_publisher/hello_publisher_node” 이런 식으로 뜨게 됩니다.

우리가 ‘ros2 run hello_publisher hello_publisher_node’라고 명령어를 입력하는게 실행 파일인 ‘hello_publisher_node’를 실행하는 것이기도 합니다.

그래서 argv[0]를 한 번 출력해보시면 확인할 수 있습니다. 그리고 ‘ros2 run hello_publisher hello_publisher_node this is bgab code’라고 굳이 입력했다고 생각해보고 이걸 출력하면 아래와 같이 작동합니다.

//ros2 run hello_publisher hello_publisher_node this is bgab code를 터미널에 입력하여 프로그램을 실행한 상황!
int main(int argc, char **argv)
{
    for (int i = 0; i < argc; i++)
    {
        std::cout << argv[i] << std::endl;
    }
}
// 출력결과
// argv[0] : /home/user/ros2_ws/install/lib/hello_publisher/hello_publisher_node
// argv[1] : this
// argv[2] : is
// argv[3] : bgab
// argv[4] : code

그리고 rclcpp::init() 함수 내부적으로 살펴보면 해당 명령어들을 for문을 통해 위와 같이 하나씩 살펴보며, 유효한 명령어인지 판단하여 추가적으로 파라미터로 활용되는게 init() 함수의 역할 중 하나입니다.

그럼 init 함수 내부를 살펴봅시다.

rclcpp::init 함수 vscode

rclcpp 라이브러리를 Github를 통해 다운로드 받았고 해당 코드에서 init 함수를 조사해보니 위와 같이 utilities.cpp 소스 파일에서 어떤 식으로 구현하고 있는지 확인할 수 있었습니다.

namespace rclcpp
{

void
init(
  int argc,
  char const * const * argv,
  const InitOptions & init_options,
  SignalHandlerOptions signal_handler_options)
{
  using rclcpp::contexts::get_global_default_context;
  get_global_default_context()->init(argc, argv, init_options);
  // Install the signal handlers.
  install_signal_handlers(signal_handler_options);
}

namespace가 rclcpp로 시작하여 함수 init까지해서 위에서 봤던 그 rclcpp::init 함수임을 알 수 있습니다. 그런데 명령행 인수 뒤로 2가지가 더 있습니다.

이 같은 경우 헤더를 보시면 이해가 될 텐데요.

RCLCPP_PUBLIC
void
init(
  int argc,
  char const * const * argv,
  const InitOptions & init_options = InitOptions(), 
  //-> 기본값(InitOptions() 함수의 리턴값)이 제공된다.
  SignalHandlerOptions signal_handler_options = SignalHandlerOptions::All); 
  //-> 기본값(SignalHandlerOptions::All)이 제공된다.

헤더에서 함수 선언을 보시면 위와 같이 작성했는데, 뒤의 2개의 매개변수, init_options와 signal_handler_options는 기본값이 제공되기 때문에 제공된 매개변수 2개를 생략해도 됩니다.

get_global_default_context()->init(argc, argv, init_options);

어떠한 context를 주체로 init 함수가 또 호출되는군요. 너무 길어져서 구조 세부내용까진 살피지 않고 Context라는 클래스에서 init함수를 호출한다는 것만 알고 다음을 봅시다.

install_signal_handlers(signal_handler_options);

//시그널 옵션은 아래와 같이 선언해서 사용 중
/// Option to indicate which signal handlers rclcpp should install.
enum class SignalHandlerOptions
{
  /// Install both sigint and sigterm, this is the default behavior.
  All,
  /// Install only a sigint handler.
  SigInt,
  /// Install only a sigterm handler.
  SigTerm,
  /// Do not install any signal handler.
  None,
};

시그널(signal) 핸들러의 옵션을 사용하며 이는 Linux 운영체제라면 공통적으로 존재하는 일종의 인터럽트 역할을 하는 개념입니다. 여러분이 터미널에서 실행 중일 때 Ctrl + C를 누르면 SIGINT가 발생하고 이를 return 값으로 하여 실행 중인 프로세스를 종료시킬 수 있습니다.

자세한 내용은 다른 포스팅을 참고해주시고, 어쨌든 이 함수 안에서 이러한 시그널 핸들러를 구현하고 있습니다. 이제 Context 클래스의 init함수를 타고 들어가봅니다.

3.3. ‘Context::init()’ 함수

rclcpp::init() 함수 내부에서 호출되는 Context::init() 함수는 ROS 2의 주요 초기화 과정을 담당합니다. 이 함수는 ROS 2의 다양한 설정을 초기화하고, 시스템의 상태를 관리합니다.


void
Context::init(
  int argc,
  char const * const * argv,
  const rclcpp::InitOptions & init_options)
{
  std::lock_guard<std::recursive_mutex> init_lock(init_mutex_);
  if (this->is_valid()) {
    throw rclcpp::ContextAlreadyInitialized();
  }
  this->clean_up();
  rcl_context_t * context = new rcl_context_t;
  if (!context) {
    throw std::runtime_error("failed to allocate memory for rcl context");
  }
  *context = rcl_get_zero_initialized_context();
  rcl_ret_t ret = rcl_init(argc, argv, init_options.get_rcl_init_options(), context);
  if (RCL_RET_OK != ret) {
    delete context;
    rclcpp::exceptions::throw_from_rcl_error(ret, "failed to initialize rcl");
  }
  rcl_context_.reset(context, __delete_context);

  if (init_options.auto_initialize_logging()) {
    logging_mutex_ = get_global_logging_mutex();
    std::lock_guard<std::recursive_mutex> guard(*logging_mutex_);
    size_t & count = get_logging_reference_count();
    if (0u == count) {
      ret = rcl_logging_configure_with_output_handler(
        &rcl_context_->global_arguments,
        rcl_init_options_get_allocator(init_options.get_rcl_init_options()),
        rclcpp_logging_output_handler);
      if (RCL_RET_OK != ret) {
        rcl_context_.reset();
        rclcpp::exceptions::throw_from_rcl_error(ret, "failed to configure logging");
      }
    } else {
      RCLCPP_WARN(
        rclcpp::get_logger("rclcpp"),
        "logging was initialized more than once");
    }
    ++count;
  }

  try {
    std::vector<std::string> unparsed_ros_arguments = detail::get_unparsed_ros_arguments(
      argc, argv, &(rcl_context_->global_arguments), rcl_get_default_allocator());
    if (!unparsed_ros_arguments.empty()) {
      throw exceptions::UnknownROSArgsError(std::move(unparsed_ros_arguments));
    }

    init_options_ = init_options;

    weak_contexts_ = get_weak_contexts();
    weak_contexts_->add_context(this->shared_from_this());
  } catch (const std::exception & e) {
    ret = rcl_shutdown(rcl_context_.get());
    rcl_context_.reset();
    if (RCL_RET_OK != ret) {
      std::ostringstream oss;
      oss << "While handling: " << e.what() << std::endl <<
        "    another exception was thrown";
      rclcpp::exceptions::throw_from_rcl_error(ret, oss.str());
    }
    throw;
  }
}

으… C/C++이 익숙하지 않은 사람에겐 지옥같을 겁니다. init 함수 안에 적힌 저 코드들이 그냥 외계어로 보일 뿐이죠. 하나하나 짚고 가기에는 초심자에게 한달도 턱없이 부족할 겁니다. 필요한 부분만 잘라서 저라면 어떤 식으로 훑어보게 되는지도 조금 보여주면서 살펴보겠습니다.

// void
// Context::init(
//   int argc,
//   char const * const * argv,
//   const rclcpp::InitOptions & init_options)
// {
  //std::lock_guard<std::recursive_mutex> init_lock(init_mutex_);
//   if (this->is_valid()) {
//     throw rclcpp::ContextAlreadyInitialized();
//   }
//   this->clean_up();
//   rcl_context_t * context = new rcl_context_t;
//   if (!context) {
//     throw std::runtime_error("failed to allocate memory for rcl context");
//   }
//   *context = rcl_get_zero_initialized_context();
  rcl_ret_t ret = rcl_init(argc, argv, init_options.get_rcl_init_options(), context);
  if (RCL_RET_OK != ret) {
    // delete context;
    rclcpp::exceptions::throw_from_rcl_error(ret, "failed to initialize rcl");
  }
//   rcl_context_.reset(context, __delete_context);

제 시야에서는 위와 같이 주석처리되는군요. 자, 주석 안 된 내용 중 가장 위의 줄 rcl_ret_t라는 어떠한 리턴 타입을 선언하고 rcl_init() 함수를 호출하고 또 argc, argv, 그리고 init_options를 입력해서 넘겨주는군요. 이 정도만 인지하면 충분할 것 같습니다.

그리고 ret가 정상적인 값이 아닐 경우 rcl_init() 프로세스가 제대로 처리된게 아닐테니 에러를 호출하는구나 짐작하게 됩니다.

그럼 ‘rcl’이라는 라이브러리의 존재를 알 수 있으며, 여기서 rcl_init() 함수는 ROS2의 하위 계층에서 실제 초기화 작업을 수행합니다.

//   if (init_options.auto_initialize_logging()) {
//     logging_mutex_ = get_global_logging_mutex();
//     std::lock_guard<std::recursive_mutex> guard(*logging_mutex_);
//     size_t & count = get_logging_reference_count();
//     if (0u == count) {
//       ret = rcl_logging_configure_with_output_handler(
//         &rcl_context_->global_arguments,
//         rcl_init_options_get_allocator(init_options.get_rcl_init_options()),
//         rclcpp_logging_output_handler);
//       if (RCL_RET_OK != ret) {
//         rcl_context_.reset();
//         rclcpp::exceptions::throw_from_rcl_error(ret, "failed to configure logging");
//       }
//     } else {
//       RCLCPP_WARN(
//         rclcpp::get_logger("rclcpp"),
//         "logging was initialized more than once");
//     }
//     ++count;
//   }

//   try {
//     std::vector<std::string> unparsed_ros_arguments = detail::get_unparsed_ros_arguments(
//       argc, argv, &(rcl_context_->global_arguments), rcl_get_default_allocator());
//     if (!unparsed_ros_arguments.empty()) {
//       throw exceptions::UnknownROSArgsError(std::move(unparsed_ros_arguments));
//     }

//     init_options_ = init_options;

//     weak_contexts_ = get_weak_contexts();
//     weak_contexts_->add_context(this->shared_from_this());
  } catch (const std::exception & e) {
    ret = rcl_shutdown(rcl_context_.get());
    rcl_context_.reset();
    // if (RCL_RET_OK != ret) {
    //   std::ostringstream oss;
    //   oss << "While handling: " << e.what() << std::endl <<
    //     "    another exception was thrown";
    //   rclcpp::exceptions::throw_from_rcl_error(ret, oss.str());
    // }
    throw;
  }

그럼 나머지는 대충 훑어 넘기고 catch를 통해 에러가 발생되면 rcl_shutdown()을 호출하면서 rcl_init으로 로직의 시작을 알리고 이게 제대로 안 되면 rcl_shutdown을 try~catch를 통해 하게끔 만들었구나 정도가 대략적으로 보입니다. 그리고 에러 상황마다 rcl_context_를 reset하는 정도가 보이는군요.

이제 rcl_init을 타고 들어가기 위해 rcl 라이브러리를 살펴보겠습니다.

3.4. ‘rcl_init()’ 함수와 ROS_DOMAIN_ID

rcl_init() 함수는 ROS 2 시스템의 초기화를 담당하며, 특히 ROS_DOMAIN_ID 환경 변수를 사용하여 도메인 ID를 설정합니다. 이 과정은 ROS 2 노드 간의 통신을 동일한 도메인 내에서만 이루어지도록 제한합니다.

rcl.c 파일

아래는 rcl/init.c 소스코드에 구현되어 있는 rcl_init 함수 내부입니다.

rcl_ret_t
rcl_init(
  int argc,
  char const * const * argv,
  const rcl_init_options_t * options,
  rcl_context_t * context)
{
  rcl_ret_t fail_ret = RCL_RET_ERROR;

  if (argc > 0) {
    RCL_CHECK_ARGUMENT_FOR_NULL(argv, RCL_RET_INVALID_ARGUMENT);
    for (int i = 0; i < argc; ++i) {
      RCL_CHECK_ARGUMENT_FOR_NULL(argv[i], RCL_RET_INVALID_ARGUMENT);
    }
  } else {
    if (NULL != argv) {
      RCL_SET_ERROR_MSG("argc is <= 0, but argv is not NULL");
      return RCL_RET_INVALID_ARGUMENT;
    }
  }
  RCL_CHECK_ARGUMENT_FOR_NULL(options, RCL_RET_INVALID_ARGUMENT);
  RCL_CHECK_ARGUMENT_FOR_NULL(options->impl, RCL_RET_INVALID_ARGUMENT);
  rcl_allocator_t allocator = options->impl->allocator;
  RCL_CHECK_ALLOCATOR(&allocator, return RCL_RET_INVALID_ARGUMENT);
  RCL_CHECK_ARGUMENT_FOR_NULL(context, RCL_RET_INVALID_ARGUMENT);

  RCUTILS_LOG_DEBUG_NAMED(
    ROS_PACKAGE_NAME,
    "Initializing ROS client library, for context at address: %p", (void *) context);

  // test expectation that given context is zero initialized
  if (NULL != context->impl) {
    // note that this can also occur when the given context is used before initialization
    // i.e. it is declared on the stack but never defined or zero initialized
    RCL_SET_ERROR_MSG("rcl_init called on an already initialized context");
    return RCL_RET_ALREADY_INIT;
  }

rcl_init함수는 L45에서 L243에 이를 정도로 길기 때문에 크게 크게 잘라 부분적으로 보겠습니다. 비슷한 구조로 코드들이 기능에 따라 감싸져있는게 보입니다.

// rcl_ret_t
// rcl_init(
//   int argc,
//   char const * const * argv,
//   const rcl_init_options_t * options,
//   rcl_context_t * context)
// {
//   rcl_ret_t fail_ret = RCL_RET_ERROR;

//   if (argc > 0) {
//     RCL_CHECK_ARGUMENT_FOR_NULL(argv, RCL_RET_INVALID_ARGUMENT);
    for (int i = 0; i < argc; ++i) {
      RCL_CHECK_ARGUMENT_FOR_NULL(argv[i], RCL_RET_INVALID_ARGUMENT);
    }
//   } else {
//     if (NULL != argv) {
//       RCL_SET_ERROR_MSG("argc is <= 0, but argv is not NULL");
//       return RCL_RET_INVALID_ARGUMENT;
//     }
//   }

눈에 띄는 for 문이 보이네요. 앞서 설명한 명령행 예제와 비슷한 구조처럼 있습니다. argv 명령행 배열들, 여러분이 터미널에 입력한 명령어를 잘라서 NULL인지 ROS2에서 사용하는 인자(Argument)에 해당하는지 판별을 여기서 이루어지는구나 짐작할 수 있습니다.

좀 더 아래로 내려가봅시다.

//   // Set the instance id.
//   uint64_t next_instance_id = rcutils_atomic_fetch_add_uint64_t(&__rcl_next_unique_id, 1);
//   if (0 == next_instance_id) {
//     // Roll over occurred, this is an extremely unlikely occurrence.
//     RCL_SET_ERROR_MSG("unique rcl instance ids exhausted");
//     // Roll back to try to avoid the next call succeeding, but there's a data race here.
//     rcutils_atomic_store(&__rcl_next_unique_id, -1);
//     goto fail;
//   }
//   rcutils_atomic_store((atomic_uint_least64_t *)(&context->instance_id_storage), next_instance_id);
//   context->impl->init_options.impl->rmw_init_options.instance_id = next_instance_id;

  size_t * domain_id = &context->impl->init_options.impl->rmw_init_options.domain_id;
  if (RCL_DEFAULT_DOMAIN_ID == *domain_id) {
    // Get actual domain id based on environment variable.
    ret = rcl_get_default_domain_id(domain_id);
//     if (RCL_RET_OK != ret) {
//       fail_ret = ret;
//       goto fail;
//     }
//   }

domain_id가 눈에 들어옵니다. ‘export ROS_DOMAIN_ID=7’과 같이 명령어를 입력하거나 bashrc에 입력해둔게 떠오르죠? Linux의 환경변수 설정값들도 C++ 코드에서 불러와서 작용이 가능합니다.

std::getenv()라는 함수인데요. 환경변수와 셸, 그리고 커널에 대한 상세 내용은 다른 포스팅을 통해서 개념을 익혀보시길 바랍니다. 터미널에 env를 입력해 여러분의 터미널의 셸에서 설정된 환경변수가 무엇이 있는지 확인해보시길 바랍니다.

rcl_get_default_domain_id() 함수 내부를 보면 ‘rcutils_get_env()’ 함수를 호출하는데 해당 함수 내부에 보시면 아래와 같이 getenv()함수를 사용하는게 보입니다.

const char *
rcutils_get_env(const char * env_name, const char ** env_value)
{
  RCUTILS_CAN_RETURN_WITH_ERROR_OF("some string error");

  if (NULL == env_name) {
    return "argument env_name is null";
  }
  if (NULL == env_value) {
    return "argument env_value is null";
  }

  // TODO(Suyash458): getenv is deprecated on Windows; consider using getenv_s instead
  *env_value = getenv(env_name); //---> 특정 환경변수 이름에 대한 값을 얻어올 수 있다.

  if (NULL == *env_value) {
    *env_value = "";
  }
  return NULL;
}

std::getenv(“HOME”)이면 “/home/user/”라는 디렉토리에 해당하는 문자를 얻는 것이고 std::getenv(“ROS_DOMAIN_ID”)를 쓰면 여러분이 bashrc에 적었뒀거나 터미널에서 직접 입력했을 DOMAIN ID 값을 가져오게 되는 것이죠.

이런 식으로 프로그램 외적으로도 다양한 방식으로 상호작용이 되기에 Linux 운영체제에 대한 배경지식도 갖추어야 ROS2를 활용하고 이해하는데 도움이 됩니다.

또 내려가 봅시다.

  // Initialize rmw_init.
  rmw_ret_t rmw_ret = rmw_init(
    &(context->impl->init_options.impl->rmw_init_options),
    &(context->impl->rmw_context));
//   if (RMW_RET_OK != rmw_ret) {
//     RCL_SET_ERROR_MSG(rmw_get_error_string().str);
//     fail_ret = rcl_convert_rmw_ret_to_rcl_ret(rmw_ret);
//     goto fail;
//   }

//   TRACEPOINT(rcl_init, (const void *)context);

//   return RCL_RET_OK;
// fail:
//   __cleanup_context(context);
//   return fail_ret;
// }

rcl_init() 함수 끝에 다다라서야 rmw_init() 라는 함수가 눈에 띄는군요. rmw, Ros Middle Ware 라이브러리를 init하는구나하고 이제 짐작되나요?

3.5. DDS와의 연결

ROS 2의 rcl_init() 함수는 최종적으로 rmw_init() 함수를 호출하여 DDS와의 연결을 설정합니다. rmw_init() 함수는 ROS2의 미들웨어 계층인 RMW(Ros Middle Ware) 라이브러리를 초기화하여, DDS 통신을 위한 준비를 마칩니다.

이 과정에서 ROS 2는 DDS 기반의 통신 환경을 설정하며, ROS 2 노드 간의 데이터 교환이 가능해집니다. 이처럼 ROS 2는 C++ 코드의 초기화 과정을 통해 DDS와의 통신 연결을 설정하고, 실시간 데이터 교환을 위한 기반을 마련합니다.

init 함수를 시작으로 다양한 구조체와 라이브러리의 조합들로 구성되어 있음을 볼 수 있었습니다. 초기화 과정에서 문제가 생기더라도 main 문에서 ROS 구조체들이 메모리 할당과 해제가 자연스럽게 이루어집니다.

다만 코드의 일부를 보여줬다시피 구조가 여러 겹으로 감싸져있는 것을 알 수 있습니다. 그래서 높은 최적화를 생각한다면 ROS의 편의성과 이식성이 특정한 기능을 하도록 만들어둔 라이브러리, 인터페이스들을 ROS로 감싸서 프로세스를 거친다는 점에서 마냥 효율적이다는 건 아니다라고 보는 의견도 있는 겁니다.

4. DDS와 Fast-RTPS의 역할

4.1. Fast-RTPS 개요 및 역할

ROS 2에서 미들웨어로 사용되는 DDS(Data Distribution Service)는 제품명에 따라 다양한 이름으로 불립니다. 그 중 대표적인 오픈 소스 제품으로는 Fast DDS와 Cyclone DDS가 있습니다. 이들 DDS 구현체는 ROS 2의 통신을 담당하며, C++로 작성된 ROS 미들웨어 라이브러리인 rmw_fastrtps_cpp과 rmw_cyclone_dds를 통해 사용됩니다.

그 중에서도 ROS2에서 default로 사용되고 있는 rmw_fastrtp_cpp에 대한 소스코드를 살펴볼 겁니다.

Fast-RTPS? & Fast DDS?

Fast-RTPS는 원래 eProsima에서 개발한 DDS 구현체의 초기 이름으로 Real-Time Publish-Subscribe(뭔가 익숙한 이름이죠?ㅎㅎ) 프로토콜을 기반으로 하여 개발되었기 때문에 해당 이름이 사용되었습니다. 그런데 DDS 통신을 담당하는 여러 미들웨어 중 하나로 사용되기도 하고 더 넓은 범위의 DDS 표준을 구현하고 있음을 강조하기 위해 현재의 ‘Fast DDS’로 이름이 변경되었습니다.

Fast DDS의 주요 역할은 다음과 같습니다:

1. 데이터 교환 : ROS 2에서 노드 간 데이터를 교환하는 역할을 하며, 퍼블리셔(Publisher)와 서브스크라이버(Subscriber) 간의 통신을 지원합니다.

2. 실시간 성능 보장 : 실시간 애플리케이션을 위한 낮은 지연 시간과 높은 신뢰성을 제공합니다.

3. QoS(Quality of Service) 지원 : 통신의 신뢰성, 우선순위, 대역폭 관리 등을 가능하게 하는 다양한 QoS 정책을 제공합니다.

4. 플랫폼 독립성 : 여러 운영 체제와 플랫폼에서 독립적으로 동작할 수 있습니다.

4.2. ROS 2에서 Fast-RTPS와의 연동

ROS 2에서 Fast DDS와의 연동은 DomainParticipant, Publisher, Subscriber 등의 객체를 생성하고 설정하는 과정으로 이루어집니다. 이 객체들은 ROS 2 노드가 DDS를 통해 데이터를 주고받는 데 핵심적인 역할을 합니다.

데이터 교환은 ROS 2에서 사용하는 것과 동일한 개념입니다. 노드 간에 데이터를 주고받기 위해 Topic을 사용하며, Topic은 데이터 타입과 이름을 통해 정의됩니다. 데이터는 ‘Domain’을 경유하여 Publisher와 Subscriber 간에 오가며, 이는 아래 그림처럼 직관적으로 표현될 수 있습니다.

그림3

4.3 QoS 설정의 중요성 및 구현

Fast DDS에서 제공하는 QoS 정책은 ROS 2 통신에 중요한 영향을 미칩니다. 예를 들어, PARTICIPANT_QOS_DEFAULT와 같은 QoS 설정은 노드 간의 데이터 전송 신뢰성, 우선순위 등을 조정하여 실시간 성능을 보장합니다.

ROS_DOMAIN_ID 환경 변수는 노드 간 데이터 접근을 제한하는 방법 중 하나입니다. 별도의 Domain 변경 없이 동일 네트워크를 사용하면, 모든 노드가 데이터에 접근할 수 있어 예상치 못한 혼선을 초래할 수 있습니다. (예시: 정상적으로 동작하던 프로그램이 갑자기 심한 랙을 겪는 상황 등)

이를 방지하기 위해 ROS 2에서는 Domain을 구분하는 설정이 필요합니다.

4.4. 코드 분석: create_publisher() 함수

이제 ROS 2에서 Fast DDS와 연동되는 코드를 살펴보겠습니다. create_publisher() 함수는 rmw_fastrtps_cpp 라이브러리의 publisher.cpp에 구현되어 있으며, 퍼블리셔를 생성하는 과정을 담당합니다. 아래 코드는 이 함수의 일부를 발췌한 것입니다.

rmw_fastrtps_cpp::create_publisher(
  const CustomParticipantInfo * participant_info,
  const rosidl_message_type_support_t * type_supports,
  const char * topic_name,
  const rmw_qos_profile_t * qos_policies,
  const rmw_publisher_options_t * publisher_options,
  bool keyed,
  bool create_publisher_listener)
{
    //(중략)
    // Create Topic and Type names
    auto callbacks = static_cast<const message_type_support_callbacks_t *>(type_support->data);
    std::string type_name = _create_type_name(callbacks);
    auto topic_name_mangled =
        _create_topic_name(qos_policies, ros_topic_prefix, topic_name).to_string();

    //(중략)

    /////
    // Get Participant and Publisher
    eprosima::fastdds::dds::DomainParticipant * dds_participant = participant_info->participant_;
    eprosima::fastdds::dds::Publisher * publisher = participant_info->publisher_;

이 코드에서는 DomainParticipant와 Publisher 객체가 생성 및 설정되는 것을 볼 수 있습니다. 이들은 ROS 2에서 퍼블리셔가 데이터를 송신하는 데 핵심적인 역할을 합니다.

  • eprosima::fastdds::dds::DomainParticipant * dds_participant
  • eprosima::fastdds::dds::Publisher * publisher

이번엔 그냥 주석없이 그대로 코드를 조금 나열해보았는데 키워드들이 뭔가 눈에 익숙한 단어들이라고 느낌이 들죠?

해당 Fast DDS를 기반으로 구조를 다듬어진게 여러분이 ROS에서 사용하시면서 보던 Publisher, Subscription인 것이죠.

대망의 Fast DDS를 타고 들어가봅니다. 이제 여러분도 익숙한 이름의 클래스와 구조체들이 나타납니다.

4.5. Fast DDS 구조와 C++ 코드 설명

Fast DDS는 매우 복잡한 구조를 가지고 있으며, 다양한 클래스와 네임스페이스로 추상화되어 있습니다. 예를 들어, Publisher 클래스는 Fast DDS의 핵심 요소 중 하나로, 데이터를 송신하는 역할을 합니다:

//Fast-DDS-master/include/fastdds/dds/publisher/Publisher.hpp

namespace eprosima {
namespace fastdds {
//(중략)
namespace dds {

class DomainParticipant;
class PublisherListener;
class PublisherImpl;
class DataWriter;
class DataWriterListener;
class Topic;

/**
 * Class Publisher, used to send data to associated subscribers.
 *
 * @ingroup FASTDDS_MODULE
 */
class Publisher : public DomainEntity
{
protected:

    friend class PublisherImpl;
    friend class DomainParticipantImpl;

DDS 통신을 위해 복잡한 형태로 추상화된 이 구조는 소켓 통신 레벨까지 연결됩니다. 아래는 UDP 소켓을 구현한 코드의 일부입니다:

//Fast-DDS-master/src/cpp/rtps/transport/UDPChannelResource.h
namespace eprosima {
namespace fastdds {
namespace rtps {

class TransportReceiverInterface;
class UDPTransportInterface;

#if defined(ASIO_HAS_MOVE)
// Typedefs
class eProsimaUDPSocket : public asio::ip::udp::socket //소켓 발견!!
{
public:

    explicit eProsimaUDPSocket(
            asio::io_service& io_service)
        : asio::ip::udp::socket(io_service)
    {
    }

이 코드는 boost 라이브러리를 활용하여 UDP 소켓을 구성하는 부분입니다. Fast DDS는 이러한 저수준 네트워크 구성 요소를 통해 데이터를 전송하며, ROS 2의 퍼블리셔와 서브스크라이버 간의 실시간 통신을 가능하게 합니다.

다음 편에서 계속해서 이어집니다.

참조

웹사이트

👉rclcpp C++ 라이브러리(Github-ver.Humble)

👉rcl C++ 라이브러리(Github-ver.Humble)

👉rmw C++ 라이브러리(Github-ver.Humble)

👉Fast DDS Documentation

👉Fast DDS C++ 예제

도서

📚 ROS2로 시작하는 로봇 프로그래밍

📚 리눅스 API의 모든것 Vol. 1 기초 리눅스 API