토픽 프로그래밍(C++)

두부김치·2024년 2월 19일
0

ROS2

목록 보기
24/29

1. 토픽(Topic)

토픽(Topic)은 비동기식 양뱡향 메시지 송수신 방식으로 메시지를 퍼블리시하는 퍼블리셔(Publisher)와 메시지를 서브스크라이브 하는 서브스크라이버(Subscriber) 간의 통신이다. 이는 1:1 통신을 기본으로 하지만 복수의 노드에서 하나의 토픽을 송수신하는 1:N 도 가능하고 그 구성방식에 따라 N:1, N:N 통신도 가능하다. 이는 ROS 메시지 통신에서 가장 널리 사용되는 통신 방법이다.

우리는 이번 장에서 아래 그림과 같이 토픽을 생성한 시간과 연산에 사용할 변수 a와 변수 b를 퍼블리시하는 토픽 퍼블리셔와 이를 서브스크라이브 하는 토픽 서브스크라이버를 작성해 볼 것이다.

2. 토픽 퍼블리셔 코드

토픽 퍼블리셔 하는 역할을 하는 노드는 argument 노드이다. argument의 전체 소스코드는 다음과 같다.

#ifndef ARITHMETIC__ARGUMENT_HPP_
#define ARITHMETIC__ARGUMENT_HPP_

#include <chrono>
#include <memory>
#include <string>
#include <utility>

#include "rclcpp/rclcpp.hpp"

#include "msg_srv_action_interface_example/msg/arithmetic_argument.hpp"


class Argument : public rclcpp::Node
{
public:
  using ArithmeticArgument = msg_srv_action_interface_example::msg::ArithmeticArgument;

  explicit Argument(const rclcpp::NodeOptions & node_options = rclcpp::NodeOptions());
  virtual ~Argument();

private:
  void publish_random_arithmetic_arguments();
  void update_parameter();

  float min_random_num_;
  float max_random_num_;

  rclcpp::Publisher<ArithmeticArgument>::SharedPtr arithmetic_argument_publisher_;
  rclcpp::TimerBase::SharedPtr timer_;
  rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent>::SharedPtr parameter_event_sub_;
  rclcpp::AsyncParametersClient::SharedPtr parameters_client_;
};
#endif  // ARITHMETIC__ARGUMENT_HPP_
#include <cstdio>
#include <memory>
#include <string>
#include <utility>
#include <random>

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

#include "arithmetic/argument.hpp"

using namespace std::chrono_literals;

Argument::Argument(const rclcpp::NodeOptions & node_options)
: Node("argument", node_options),
  min_random_num_(0.0),
  max_random_num_(0.0)
{
  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();

  const auto QOS_RKL10V =
    rclcpp::QoS(rclcpp::KeepLast(qos_depth)).reliable().durability_volatile();

  arithmetic_argument_publisher_ =
    this->create_publisher<ArithmeticArgument>("arithmetic_argument", QOS_RKL10V);

  timer_ =
    this->create_wall_timer(1s, std::bind(&Argument::publish_random_arithmetic_arguments, this));
}

Argument::~Argument()
{
}

void Argument::publish_random_arithmetic_arguments()
{
  std::random_device rd;
  std::mt19937 gen(rd());
  std::uniform_real_distribution<float> distribution(min_random_num_, max_random_num_);

  msg_srv_action_interface_example::msg::ArithmeticArgument msg;
  msg.stamp = this->now();
  msg.argument_a = distribution(gen);
  msg.argument_b = distribution(gen);
  arithmetic_argument_publisher_->publish(msg);

  RCLCPP_INFO(this->get_logger(), "Published argument_a %.2f", msg.argument_a);
  RCLCPP_INFO(this->get_logger(), "Published argument_b %.2f", msg.argument_b);
}

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);
}

void print_help()
{
  printf("For argument 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);

  auto argument = std::make_shared<Argument>();

  rclcpp::spin(argument);

  rclcpp::shutdown();

  return 0;
}

먼저 헤더 파일(hpp)을 보면 ROS2를 다루는 데 필수적인 라이브러리들이 먼저 선언되어 있다. 각 라이브러리에 대한 간단한 기능과 링크는 다음과 같다.

  1. chrono 시간을 다루는 라이브러리(https://www.cplusplus.com/reference/chrono/)
  2. memory 동적 메모리를 다루는 라이브러리(https://www.cplusplus.com/reference/memory/?kw=memory)
  3. string 문자열을 다루는 라이브러리(https://www.cplusplus.com/reference/string/string/?kw=string)
  4. utility 서로다른 도메인을 다루는 라이브러리(https://www.cplusplus.com/reference/utility/?kw=utility)

그 다음은 rclcpp 헤더 파일과 인터페이스를 담고 있는 헤더 파일이 선언되어 있다.

#include <chrono>
#include <memory>
#include <string>
#include <utility>

#include "rclcpp/rclcpp.hpp"

#include "msg_srv_action_interface_example/msg/arithmetic_argument.hpp"

rclcpp의 Node 클래스를 상속받는 Argument 클래스에 대해 알아보자. Argument 클래스의 생성자는 rclcpp의 NodeOptions 객체를 인자로 받는다. NodeOptions 객체를 통해서는 context, arguments, intra-process communication, parameter, allocator와 같은 Node 생성을 위한 다양한 옵션을 정할 수 있다.

Arguments 클래스에는 스마트 포인터 타입의 멤버 변수 rclcpp::Publisherrclcpp::TimerBase 가 선언되어 있으며 토픽 메시지에 담을 랜덤 변수의 샘플링 범위를 정해줄 멤버 변수도 함께 확인할 수 있다. 파라미터와 관련된 멤버 변수와 함수는 추후에 다루도록 하겠다,

class Argument : public rclcpp::Node
{
public:
  using ArithmeticArgument = msg_srv_action_interface_example::msg::ArithmeticArgument;

  explicit Argument(const rclcpp::NodeOptions & node_options = rclcpp::NodeOptions());
  virtual ~Argument();

private:
  void publish_random_arithmetic_arguments();
  void update_parameter();

  float min_random_num_;
  float max_random_num_;

  rclcpp::Publisher<ArithmeticArgument>::SharedPtr arithmetic_argument_publisher_;
  rclcpp::TimerBase::SharedPtr timer_;
  rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent>::SharedPtr parameter_event_sub_;
  rclcpp::AsyncParametersClient::SharedPtr parameters_client_;
};

이제 cpp 파일을 보자. 먼저 hpp파일에서 보지 못한 라이브러리에 대한 간단한 기능과 링크를 정리해놓았다.

  1. cstdio : C 언어 표준 인풋 아웃풋 라이브러리 (http://www.cplusplus.com/reference/cstdio/)
  2. random : 랜덤 숫자 생성 라이브러리 (http://www.cplusplus.com/reference/random/?kw=random)

cmdline_parser 헤더 파일은 프로그램 실행 시 넘겨 받은 인자를 다루는 ROS2 라이브러리 이다.

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

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

#include "arithmetic/argument.hpp"

Argument 클래스 생성자에서 부모 클래스인 rclcpp::Node에 대한 선언을 알아보자. 첫 번재 매개변수에는 노드의 이름을 적고, 두 번째 매개변수에는 NodeOptions 객체를 명시한다. 퍼블리시를 위한 QoS는 rclcpp::QoS 라이브러리를 이용하였다. History 옵션은 KeepLast(Depth는 10) Reliability 옵션은 reliable, Durability로 설정하였다. Durability 옵션은 volatile로 설정하였다. 해당 QoS는 다음 publisher를 초기화 할 때 두 번째 인자로 들어가게 되고, 첫 번째 매개변수에는 메시지 통신에 사용될 토픽명을 적어준다. timer의 경우 1초당 한 번씩 publish_random_arithmetic_arguments 멤버 함수를 호출하도록 설정하였다.

Argument::Argument(const rclcpp::NodeOptions & node_options)
: Node("argument", node_options),
  min_random_num_(0.0),
  max_random_num_(0.0)
{
  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();

  const auto QOS_RKL10V =
    rclcpp::QoS(rclcpp::KeepLast(qos_depth)).reliable().durability_volatile();

  arithmetic_argument_publisher_ =
    this->create_publisher<ArithmeticArgument>("arithmetic_argument", QOS_RKL10V);

  timer_ =
    this->create_wall_timer(1s, std::bind(&Argument::publish_random_arithmetic_arguments, this));
}

publish_random_arithmetic_arguments 멤버 함수에 대해 알아보자. 해당 함수는 timer에 의해 1초당 한 번씩 호출된다. 먼저 random 라이브러리를 사용하여 min_random_num, max_random_num 사이의 랜덤한 숫자를 생성하도록 하자.

그리고 토픽 메시지 통신에서 사용할 인터페이스(msg)를 선언하자. 해당 인터페이스의 멤버 변수들을 올바르게 채워주고 난 뒤, Argument 클래스에서 초기화한 publisher를 통해 해당 인터페이스를 publish 함수로 퍼블리시한다.

마지막으로 인터페이스를 통해 퍼블리시한 랜덤한 숫자를 로그로 표시하는 코드를 확인할 수 있다.

void Argument::publish_random_arithmetic_arguments()
{
  std::random_device rd;
  std::mt19937 gen(rd());
  std::uniform_real_distribution<float> distribution(min_random_num_, max_random_num_);

  msg_srv_action_interface_example::msg::ArithmeticArgument msg;
  msg.stamp = this->now();
  msg.argument_a = distribution(gen);
  msg.argument_b = distribution(gen);
  arithmetic_argument_publisher_->publish(msg);

  RCLCPP_INFO(this->get_logger(), "Published argument_a %.2f", msg.argument_a);
  RCLCPP_INFO(this->get_logger(), "Published argument_b %.2f", msg.argument_b);
}

3. 토픽 서브스크라이버 코드

토픽 서브스크라이버 역할을 하는 Node는 calculator 노드이다. calculator 전체 소스코드는 다음과 같다.

#ifndef CALCULATOR__CALCULATOR_HPP_
#define CALCULATOR__CALCULATOR_HPP_

#include <memory>
#include <sstream>
#include <string>
#include <utility>
#include <vector>
#include <stdexcept>

#include "rclcpp/rclcpp.hpp"
#include "rclcpp_action/rclcpp_action.hpp"

#include "msg_srv_action_interface_example/msg/arithmetic_argument.hpp"
#include "msg_srv_action_interface_example/srv/arithmetic_operator.hpp"
#include "msg_srv_action_interface_example/action/arithmetic_checker.hpp"


class Calculator : public rclcpp::Node
{
public:
  using ArithmeticArgument = msg_srv_action_interface_example::msg::ArithmeticArgument;
  using ArithmeticOperator = msg_srv_action_interface_example::srv::ArithmeticOperator;
  using ArithmeticChecker = msg_srv_action_interface_example::action::ArithmeticChecker;
  using GoalHandleArithmeticChecker = rclcpp_action::ServerGoalHandle<ArithmeticChecker>;

  explicit Calculator(const rclcpp::NodeOptions & node_options = rclcpp::NodeOptions());
  virtual ~Calculator();

  float calculate_given_formula(const float & a, const float & b, const int8_t & operators);

private:
  rclcpp_action::GoalResponse handle_goal(
    const rclcpp_action::GoalUUID & uuid,
    std::shared_ptr<const ArithmeticChecker::Goal> goal);
  rclcpp_action::CancelResponse handle_cancel(
    const std::shared_ptr<GoalHandleArithmeticChecker> goal_handle);
  void execute_checker(const std::shared_ptr<GoalHandleArithmeticChecker> goal_handle);

  rclcpp::Subscription<ArithmeticArgument>::SharedPtr
    arithmetic_argument_subscriber_;

  rclcpp::Service<ArithmeticOperator>::SharedPtr
    arithmetic_argument_server_;

  rclcpp_action::Server<ArithmeticChecker>::SharedPtr
    arithmetic_action_server_;

  float argument_a_;
  float argument_b_;

  int8_t argument_operator_;
  float argument_result_;

  std::string argument_formula_;
  std::vector<std::string> operator_;
};
#endif  // CALCULATOR__CALCULATOR_HPP_
#include <memory>
#include <sstream>
#include <string>
#include <utility>
#include <vector>
#include <stdexcept>

#include "calculator/calculator.hpp"


Calculator::Calculator(const rclcpp::NodeOptions & node_options)
: Node("calculator", node_options),
  argument_a_(0.0),
  argument_b_(0.0),
  argument_operator_(0),
  argument_result_(0.0),
  argument_formula_("")
{
  RCLCPP_INFO(this->get_logger(), "Run calculator");

  operator_.reserve(4);
  operator_.push_back("+");
  operator_.push_back("-");
  operator_.push_back("*");
  operator_.push_back("/");

  this->declare_parameter("qos_depth", 10);
  int8_t qos_depth = 0;
  this->get_parameter("qos_depth", qos_depth);

  const auto QOS_RKL10V =
    rclcpp::QoS(rclcpp::KeepLast(qos_depth)).reliable().durability_volatile();

  arithmetic_argument_subscriber_ = this->create_subscription<ArithmeticArgument>(
    "arithmetic_argument",
    QOS_RKL10V,
    [this](const ArithmeticArgument::SharedPtr msg) -> void
    {
      argument_a_ = msg->argument_a;
      argument_b_ = msg->argument_b;

      RCLCPP_INFO(
        this->get_logger(),
        "Timestamp of the message: sec %ld nanosec %ld",
        msg->stamp.sec,
        msg->stamp.nanosec);

      RCLCPP_INFO(this->get_logger(), "Subscribed argument a: %.2f", argument_a_);
      RCLCPP_INFO(this->get_logger(), "Subscribed argument b: %.2f", argument_b_);
    }
  );

  auto get_arithmetic_operator =
    [this](
    const std::shared_ptr<ArithmeticOperator::Request> request,
    std::shared_ptr<ArithmeticOperator::Response> response) -> void
    {
      argument_operator_ = request->arithmetic_operator;
      argument_result_ =
        this->calculate_given_formula(argument_a_, argument_b_, argument_operator_);
      response->arithmetic_result = argument_result_;

      std::ostringstream oss;
      oss << std::to_string(argument_a_) << ' ' <<
        operator_[argument_operator_ - 1] << ' ' <<
        std::to_string(argument_b_) << " = " <<
        argument_result_ << std::endl;
      argument_formula_ = oss.str();

      RCLCPP_INFO(this->get_logger(), "%s", argument_formula_.c_str());
    };

  arithmetic_argument_server_ =
    create_service<ArithmeticOperator>("arithmetic_operator", get_arithmetic_operator);

  using namespace std::placeholders;
  arithmetic_action_server_ = rclcpp_action::create_server<ArithmeticChecker>(
    this->get_node_base_interface(),
    this->get_node_clock_interface(),
    this->get_node_logging_interface(),
    this->get_node_waitables_interface(),
    "arithmetic_checker",
    std::bind(&Calculator::handle_goal, this, _1, _2),
    std::bind(&Calculator::handle_cancel, this, _1),
    std::bind(&Calculator::execute_checker, this, _1)
  );
}

Calculator::~Calculator()
{
}

float Calculator::calculate_given_formula(
  const float & a,
  const float & b,
  const int8_t & operators)
{
  float argument_result = 0.0;
  ArithmeticOperator::Request arithmetic_operator;

  if (operators == arithmetic_operator.PLUS) {
    argument_result = a + b;
  } else if (operators == arithmetic_operator.MINUS) {
    argument_result = a - b;
  } else if (operators == arithmetic_operator.MULTIPLY) {
    argument_result = a * b;
  } else if (operators == arithmetic_operator.DIVISION) {
    argument_result = a / b;
    if (b == 0.0) {
      RCLCPP_ERROR(this->get_logger(), "ZeroDivisionError!");
      argument_result = 0.0;
      return argument_result;
    }
  } else {
    RCLCPP_ERROR(
      this->get_logger(),
      "Please make sure arithmetic operator(plus, minus, multiply, division).");
    argument_result = 0.0;
  }

  return argument_result;
}

rclcpp_action::GoalResponse Calculator::handle_goal(
  const rclcpp_action::GoalUUID & uuid,
  std::shared_ptr<const ArithmeticChecker::Goal> goal)
{
  (void)uuid;
  (void)goal;
  return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
}

rclcpp_action::CancelResponse Calculator::handle_cancel(
  const std::shared_ptr<GoalHandleArithmeticChecker> goal_handle)
{
  RCLCPP_INFO(this->get_logger(), "Received request to cancel goal");
  (void)goal_handle;
  return rclcpp_action::CancelResponse::ACCEPT;
}

void Calculator::execute_checker(const std::shared_ptr<GoalHandleArithmeticChecker> goal_handle)
{
  RCLCPP_INFO(this->get_logger(), "Execute arithmetic_checker action!");
  rclcpp::Rate loop_rate(1);

  auto feedback_msg = std::make_shared<ArithmeticChecker::Feedback>();
  float total_sum = 0.0;
  float goal_sum = goal_handle->get_goal()->goal_sum;

  while ((total_sum < goal_sum) && rclcpp::ok()) {
    total_sum += argument_result_;
    feedback_msg->formula.push_back(argument_formula_);
    if (argument_formula_.empty()) {
      RCLCPP_WARN(this->get_logger(), "Please check your formula");
      break;
    }
    RCLCPP_INFO(this->get_logger(), "Feedback: ");
    for (const auto & formula : feedback_msg->formula) {
      RCLCPP_INFO(this->get_logger(), "\t%s", formula.c_str());
    }
    goal_handle->publish_feedback(feedback_msg);
    loop_rate.sleep();
  }

  if (rclcpp::ok()) {
    auto result = std::make_shared<ArithmeticChecker::Result>();
    result->all_formula = feedback_msg->formula;
    result->total_sum = total_sum;
    goal_handle->succeed(result);
  }
}

이 소스코드는 토픽 서브스크라이버, 서비스 서버, 액션 서버를 모두 포함하고 있어서 매우 길다. 따라서 전체 코드중 토픽 서브스크라이버 부분만 살펴보도록 하자.

Calculator 클래스는 토픽 퍼블리셔 노드와 마찬가지로 rclcpp::Node 를 상속받고 있으며 생성자에서 calculator 노드로 초기화되었다. 그 뒤 위에서와 마찬가지로 QoS는 rclcpp::QoS 라이브러리를 이용하여 History 옵션은 KeepLast(depth는 10), Reliability 옵션은 reliable, Durability 옵션은 volatile로 설정하였다.

이제 subcriber에 대해 살펴보자. subscriber는 rclcpp::Node 의 멤버 함수 create_subscription을 통해 초기화되며 해당 함수는 토픽명과 QoS 그리고 콜백 함수 매개변수로 구성되어 있다. 토픽명과 QoS는 Argument 클래스에서 입력했던 것과 동일하게 입력해 주었고, 콜백 함수는 std::bind 함수를 사용하지 않고 람다(Lamda)표현식을 이용하였다.

콜백 함수를 보면 매개변수를 통해 서브스크라이브한 토픽 메시지에 접근하여 멤버 변수에 저장하고 있다. 마지막으로 수신받은 시간과 전달받은 데이터를 로그로 나타내는 코드를 확인할 수 있다.

 const auto QOS_RKL10V =
    rclcpp::QoS(rclcpp::KeepLast(qos_depth)).reliable().durability_volatile();

  arithmetic_argument_subscriber_ = this->create_subscription<ArithmeticArgument>(
    "arithmetic_argument",
    QOS_RKL10V,
    [this](const ArithmeticArgument::SharedPtr msg) -> void
    {
      argument_a_ = msg->argument_a;
      argument_b_ = msg->argument_b;

      RCLCPP_INFO(
        this->get_logger(),
        "Subscribed at: sec %ld nanosec %ld",
        msg->stamp.sec,
        msg->stamp.nanosec);

      RCLCPP_INFO(this->get_logger(), "Subscribed argument a : %.2f", argument_a_);
      RCLCPP_INFO(this->get_logger(), "Subscribed argument b : %.2f", argument_b_);
    }
  );

4. 토픽 퍼블리셔, 서브스크라이버 복습

1) 토픽 퍼블리셔(데이터를 송신하는 프로그램)

1) Node 설정
2) QoS 설정
3) create_publisher 설정 (+ timer 설정)
4) 퍼블리시 함수 작성

2) 토픽 서브스크라이버(데이터를 수신하는 프로그램)

1) Node 설정
2) QoS 설정
3) create_subscription 설정
4) 서브스크라이브 함수 작성

5. 노드 실행 코드

이번 장에서 사용할 두 개의 노드 실행 명령어는 다음과 같다. calculator가 토픽 서브스크라이버 노드이고, argument는 토픽 퍼블리셔 노드이다.

$ ros2 run topic_service_action_rclcpp_example calculator
$ ros2 run topic_service_action_rclcpp_example argument

이 두개의 노드를 실행할 수 있도록 설정한 부분은 빌드 설정 파일(CMakeLists.txt)에서 확인할 수 있다. CMake의 add_executable 명령어는 main 함수가 포함된 소스파일을 실행 가능하도록 만들어 준다. 그 첫번째 매개변수에는 실행명을 넣고, 다음 매개변수에는 main 함수가 포함된 파일의 이름을 넣어준다. 필요하다면 그 다음 매개변수로 main 함수의 의존 라이브러리가 담긴 파일의 이름을 넣어준다. 이를 통해 우리는 ros2 run 명령어를 이용하여 argument와 calculator 노드를 실행할 수 있다.

add_executable(argument src/arithmetic/argument.cpp)
add_executable(calculator src/calculator/main.cpp src/calculator/calculator.cpp)

argument.cpp 파일의 main 함수를 확인해보자. cmdline_parser 라이브러리의 함수를 사용하여 건네받은 인자 중에 "-h"가 있다면 print_help() 함수를 호출하고 함수를 빠져나가는 것을 먼저 확인할 수 있다. 추후 강좌를 통해 cmdline_parser 라이브러리를 이용하여 이용하여 Node에 인자를 전달하는 방법에 대해 설명하겠다.

rclcpp::init 함수를 통해 namespace, remap 등을 포함하는 ROS2 argument 를 전달할 수 있고, 그 다음 앞서 정의해 놓은 Argument클래스를 객체화해서 노드를 생성한다. rclcpp::spin 함수는 생성한 노드를 spin 시켜 선언된 콜백 함수가 호출될 수 있도록 한다. 마지막으로 종료(Ctrl+c)와 같은 시그널을 통해 rclcpp::shutdown 함수가 호출되어야지만 좀비 프로세스가 생성되지 않고 프로그램이 소멸된다.

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

  rclcpp::init(argc, argv);

  auto argument = std::make_shared<Argument>();

  rclcpp::spin(argument);

  rclcpp::shutdown();

  return 0;
}

ROS2 토픽 프로그래밍을 알아보았다. 이어지는 장에서는 서비스 프로그래밍 코드를 분석해보는 시간을 가져보겠다.

profile
Robotics

0개의 댓글