[ROS2] C++ 패키지 설계 및 프로그래밍(파라미터, 실행인자)

HY K·2024년 9월 21일
0

ROS2

목록 보기
16/18

이번에는 C++을 기반으로 하는 파라미터 및 실행인자 프로그래밍을 수행해보도록 하겠다.
참고한 링크는 다음과 같다.
https://cafe.naver.com/openrt/24858
https://cafe.naver.com/openrt/24861


파라미터

파라미터에 대한 설명은 이전 포스트들을 참조하자. 간단히 얘기하면, 서비스와 유사하게 작동하지만, 글로벌 변수처럼 기능하면서 노드들의 다양한 값과 특성을 실시간으로 변화시킬 수 있는 요소라고 할 수 있다. 그리고 ROS2에서는 모든 노드가 파라미터 서버를 가지고 있어서 내외부의 파라미터 클라이언트와의 실시간 통신이 가능하다.


파라미터 서버와 초기화

파라미터 서버에 파라미터를 등록하는 방법은 크게 4가지가 있다.

1. yaml 포맷의 파일 경로를 프로그램 실행 인자로 rclcpp::Node에 전달
2. ROS2 CLI를 이용한 파라미터 등록
3. rclcpp:Node의 declare, set 파라미터 함수 사용
4. 파라미터 클라이언트 API 사용

이 중 yaml 파일은 저번 파이썬 파라미터 프로그래밍에서도 알아보았다.

/**: # namespace and node name
  ros__parameters:
    qos_depth: 30
    min_random_num: 0.0
    max_random_num: 9.0

만약 namespace와 node 이름을 구체적으로 규정하고 싶다면, 다음과 같이 작성하면 된다.

/namespace: 
  /node_name:
    ros__parameters:
      foo: 30
      bar: 0.0

설정이 모두 끝난 파라미터 파일은 launch 파일에 포함시켜 노드를 실행할 때 불러오게 된다.

예를 들어 launch.py 파일을 다음과 같이 작성할 수 있다.

import os

from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node


def generate_launch_description():
    param_dir = LaunchConfiguration(
        'param_dir',
        default=os.path.join(
            get_package_share_directory('topic_service_action_rclcpp_example'),
            'param',
            'arithmetic_config.yaml'))

    return LaunchDescription([
        DeclareLaunchArgument(
            'param_dir',
            default_value=param_dir,
            description='Full path of parameter file'),

        Node(
            package='topic_service_action_rclcpp_example',
            executable='argument',
            name='argument',
            parameters=[param_dir],
            output='screen'),

        Node(
            package='topic_service_action_rclcpp_example',
            executable='calculator',
            name='calculator',
            parameters=[param_dir],
            output='screen'),
    ])

그리고 CMakeLists.txt 파일에 파라미터 폴더 경로를 꼭 지정해야만 한다.

# 중략

install(DIRECTORY launch param
  DESTINATION share/${PROJECT_NAME}
)

# 중략

파라미터 클라이언트

예시 코드를 통해서 보도록 하자.

  rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent>::SharedPtr parameter_event_sub_;
  rclcpp::AsyncParametersClient::SharedPtr parameters_client_;

Argument 클래스에서는, ParameterEvent 타입으로 선언된 토픽 서브스크라이버와 AsyncParametersClient 클래스의 스마트 포인터를 확인할 수 있다.

또한 Argument 클래스의 생성자를 보면, 먼저 파라미터를 선언하기 위해 declare_parameter 함수를 사용해 파라미터 이름과 초깃값을 지정, get_paramter 함수를 통해 파라미터 값을 읽어들이는 것을 확인할 수 있다.

  this->declare_parameter("qos_depth", 10);
  int8_t qos_depth = this->get_parameter("qos_depth").get_value<int8_t>();
  this->declare_parameter("min_random_num", 0.0);
  min_random_num_ = this->get_parameter("min_random_num").get_value<float>();
  this->declare_parameter("max_random_num", 9.0);
  max_random_num_ = this->get_parameter("max_random_num").get_value<float>();
  this->update_parameter();

또한 update_parameter 함수로 this 포인터를 통해 초기화 하고, 파라미터 서버에 어떤 이벤트가 발생하였을 때 콜백함수를 등록하고, 이를 통해 파라미터 변경을 확인할 수 있도록 코드를 작성하였다.

void Argument::update_parameter()
{
  parameters_client_ = std::make_shared<rclcpp::AsyncParametersClient>(this);
  while (!parameters_client_->wait_for_service(1s)) {
    if (!rclcpp::ok()) {
      RCLCPP_ERROR(this->get_logger(), "Interrupted while waiting for the service. Exiting.");
      return;
    }
    RCLCPP_INFO(this->get_logger(), "service not available, waiting again...");
  }

  auto param_event_callback =
    [this](const rcl_interfaces::msg::ParameterEvent::SharedPtr event) -> void
    {
      for (auto & changed_parameter : event->changed_parameters) {
        if (changed_parameter.name == "min_random_num") {
          auto value = rclcpp::Parameter::from_parameter_msg(changed_parameter).as_double();
          min_random_num_ = value;
        } else if (changed_parameter.name == "max_random_num") {
          auto value = rclcpp::Parameter::from_parameter_msg(changed_parameter).as_double();
          max_random_num_ = value;
        }
      }
    };

  parameter_event_sub_ = parameters_client_->on_parameter_event(param_event_callback);
}

실행 인자 프로그래밍

C++ 프로그램 실행 시 가장 먼지 호출되는 main 함수의 경우 2개의 매개변수를 가지고 있다.

💡 main 함수의 매개변수
1. argc : argument count의 약자로 넘겨받은 인자들의 개수
2. argv : argument vector의 약자로 문자열/포인터/배열 타입으로 넘겨받은 인자들을 저장

한편 ROS2의 실행 인자는 다음과 같이 구분된다.

💡 ROS2의 실행인자
1. --ros-args : ROS2 API와 관련된 옵션 변경이 가능하다
2. 위 옵션이 붙지 않은 인자들 : 사용자 정의 실행 인자들이다.

예를 들어 다음 명령어를 보자.

$ ros2 run topic_service_action_rclcpp_example checker -g 100 --ros-args  -r __ns:=/demo

여기서 -g 100으로 표기한 것은 사용자 정의 실행 인자이고,
--ros-args -r __ns:=/demo 라고 표기한 것은 rclcpp::init 함수의 인자로 넘겨지게 된다.

여기서는 실행 인자 프로그래밍을 포함하고 있는 checker 노드의 코드를 통해서 설행해보자.

#include <cstdio>
#include <memory>
#include <string>
#include <utility>

#include "rclcpp/rclcpp.hpp"
#include "rcutils/cmdline_parser.h"

#include "checker/checker.hpp"


void print_help()
{
  printf("For Node node:\n");
  printf("node_name [-h]\n");
  printf("Options:\n");
  printf("\t-h Help           : Print this help function.\n");
}

int main(int argc, char * argv[])
{
  if (rcutils_cli_option_exist(argv, argv + argc, "-h")) {
    print_help();
    return 0;
  }

  rclcpp::init(argc, argv);

  float goal_total_sum = 50.0;
  char * cli_option = rcutils_cli_get_option(argv, argv + argc, "-g");
  if (nullptr != cli_option) {
    goal_total_sum = std::stof(cli_option);
  }
  printf("goal_total_sum : %2.f\n", goal_total_sum);

  auto checker = std::make_shared<Checker>(goal_total_sum);

  rclcpp::spin(checker);

  rclcpp::shutdown();

  return 0;
}

먼저 헤더 파일 부분에 실행 인자를 쉽게 확인 가능한 cmdline_parser가 포함되어 있는 것을 확인할 수 있다.

#include "rcutils/cmdline_parser.h"

그리고 main 함수 안을 보면 rcutils_cli_option_exist 함수를 이용하여 -h 인자가 있는지 확인한다. 만약 -h 인자가 있다면 print_help 함수를 호출하게 된다. 이는 노드에 대한 도움말을 출력하고 main() 함수를 종료하는 코드이다.

  if (rcutils_cli_option_exist(argv, argv + argc, "-h")) {
    print_help();
    return 0;
  }

그리고

rclcpp::init(argc, argv);

이 코드를 통해 rclcpp가 --ros-args 인자를 확인 가능하도록 한다.

rcutils_cli_get_option 함수는 실행 인자를 확인하고, 그 값을 문자열 포인터로 반환해주는 역할을 한다. 해당 함수를 이용해 쉽게 여러 실행 인자를 parsing할 수 있고 문자열 포인터를 원하는 변수 타입으로 변경해 생성될 클래스의 인자로 넘겨줄 수 있다.

  float goal_total_sum = 50.0;
  char * cli_option = rcutils_cli_get_option(argv, argv + argc, "-g");
  if (nullptr != cli_option) {
    goal_total_sum = std::stof(cli_option);
  }
  printf("goal_total_sum : %2.f\n", goal_total_sum);

  auto checker = std::make_shared<Checker>(goal_total_sum);
profile
로봇, 드론, SLAM, 제어 공학 초보

0개의 댓글