멀티 액션 구조의 개념

멀티 액션 구조란 로봇이나 시스템이 여러 개의 액션을 동시에 혹은 병렬로 실행하는 것을 의미한다. ROS2에서는 액션 서버와 액션 클라이언트 간의 통신을 통해 비동기적인 작업을 수행할 수 있다. 여러 액션을 설계하고 구현할 때는 각 액션이 독립적으로 작동해야 하지만, 필요에 따라 동기화가 이루어지거나 상호 작용할 수 있어야 한다.

액션 구조 설계

액션 구조를 설계할 때는 시스템이 동시에 수행해야 할 작업들을 구체적으로 정의하고, 이를 병렬로 처리할지, 순차적으로 처리할지를 결정해야 한다. 여기서 각 액션이 서로 간섭하지 않고 독립적으로 수행되도록 설계하는 것이 중요하다. ROS2에서 이를 구현하기 위해서는 액션 서버와 클라이언트를 활용하여 각 액션을 정의하고, 해당 액션들이 서로 통신할 수 있도록 설계한다.

액션 정의

ROS2에서는 액션을 .action 파일로 정의한다. 각 액션은 목표(goal), 결과(result), 피드백(feedback)을 포함한다. 멀티 액션 구조에서는 여러 액션이 동시에 실행되므로 각 액션의 목표와 결과를 명확히 정의하고, 이들이 서로 간섭하지 않도록 독립적인 피드백 메커니즘을 설계해야 한다.

# Example.action
# 목표
float64 target

# 피드백
float64 current_progress

# 결과
bool success

이 예시는 간단한 액션 정의 파일로, 목표 값과 피드백, 그리고 성공 여부를 나타내는 결과를 포함한다. 멀티 액션 구조에서는 이러한 액션들이 여러 개 동시에 실행되며, 각 액션은 독립적인 피드백을 제공한다.

액션 서버 구현

액션 서버는 클라이언트로부터 요청을 받아 해당 작업을 처리하고 결과를 반환하는 역할을 한다. 멀티 액션 구조에서는 여러 개의 액션 서버가 필요할 수 있으며, 각 서버는 독립적으로 동작해야 한다. 서버 간의 동기화가 필요한 경우, 액션 서버 간의 통신을 고려해야 한다.

액션 서버 코드 구현

#include <rclcpp/rclcpp.hpp>
#include <rclcpp_action/rclcpp_action.hpp>
#include "example_action_msgs/action/example.hpp"

class ExampleActionServer : public rclcpp::Node
{
public:
  ExampleActionServer() : Node("example_action_server")
  {
    this->action_server_ = rclcpp_action::create_server<example_action_msgs::action::Example>(
      this,
      "example_action",
      std::bind(&ExampleActionServer::handle_goal, this, std::placeholders::_1, std::placeholders::_2),
      std::bind(&ExampleActionServer::handle_cancel, this, std::placeholders::_1),
      std::bind(&ExampleActionServer::handle_accepted, this, std::placeholders::_1));
  }

private:
  rclcpp_action::Server<example_action_msgs::action::Example>::SharedPtr action_server_;

  rclcpp_action::GoalResponse handle_goal(
    const rclcpp_action::GoalUUID & uuid,
    std::shared_ptr<const example_action_msgs::action::Example::Goal> goal)
  {
    RCLCPP_INFO(this->get_logger(), "Goal received: %f", goal->target);
    return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
  }

  rclcpp_action::CancelResponse handle_cancel(
    const std::shared_ptr<rclcpp_action::ServerGoalHandle<example_action_msgs::action::Example>> goal_handle)
  {
    RCLCPP_INFO(this->get_logger(), "Goal canceled");
    return rclcpp_action::CancelResponse::ACCEPT;
  }

  void handle_accepted(
    const std::shared_ptr<rclcpp_action::ServerGoalHandle<example_action_msgs::action::Example>> goal_handle)
  {
    std::thread{std::bind(&ExampleActionServer::execute, this, goal_handle)}.detach();
  }

  void execute(
    const std::shared_ptr<rclcpp_action::ServerGoalHandle<example_action_msgs::action::Example>> goal_handle)
  {
    RCLCPP_INFO(this->get_logger(), "Executing goal...");
    auto feedback = std::make_shared<example_action_msgs::action::Example::Feedback>();
    auto result = std::make_shared<example_action_msgs::action::Example::Result>();

    for (int i = 0; i < 100; i++) {
      if (goal_handle->is_canceling()) {
        result->success = false;
        goal_handle->canceled(result);
        RCLCPP_INFO(this->get_logger(), "Goal canceled");
        return;
      }

      feedback->current_progress = i / 100.0;
      goal_handle->publish_feedback(feedback);
      std::this_thread::sleep_for(std::chrono::milliseconds(100));
    }

    result->success = true;
    goal_handle->succeed(result);
    RCLCPP_INFO(this->get_logger(), "Goal succeeded");
  }
};

이 코드는 ROS2 액션 서버를 구현한 예시이다. 서버는 클라이언트로부터 목표를 받아 실행하며, 피드백을 전달하고 결과를 반환한다. 멀티 액션 구조에서는 이러한 서버를 여러 개 정의할 수 있으며, 각각이 독립적으로 동작한다.

액션 클라이언트 구현

멀티 액션 구조에서 클라이언트는 여러 액션 서버와 통신하며, 비동기적으로 여러 작업을 요청할 수 있다. 클라이언트는 액션 서버로부터 피드백을 받아 처리하며, 작업이 완료되면 결과를 받는다.

액션 클라이언트 코드 구현

#include <rclcpp/rclcpp.hpp>
#include <rclcpp_action/rclcpp_action.hpp>
#include "example_action_msgs/action/example.hpp"

class ExampleActionClient : public rclcpp::Node
{
public:
  ExampleActionClient() : Node("example_action_client")
  {
    this->client_ = rclcpp_action::create_client<example_action_msgs::action::Example>(
      this, "example_action");

    this->send_goal();
  }

private:
  rclcpp_action::Client<example_action_msgs::action::Example>::SharedPtr client_;

  void send_goal()
  {
    if (!this->client_->wait_for_action_server(std::chrono::seconds(10))) {
      RCLCPP_ERROR(this->get_logger(), "Action server not available after waiting");
      return;
    }

    auto goal_msg = example_action_msgs::action::Example::Goal();
    goal_msg.target = 100.0;

    auto send_goal_options = rclcpp_action::Client<example_action_msgs::action::Example>::SendGoalOptions();
    send_goal_options.goal_response_callback =
      std::bind(&ExampleActionClient::goal_response_callback, this, std::placeholders::_1);
    send_goal_options.feedback_callback =
      std::bind(&ExampleActionClient::feedback_callback, this, std::placeholders::_1, std::placeholders::_2);
    send_goal_options.result_callback =
      std::bind(&ExampleActionClient::result_callback, this, std::placeholders::_1);

    this->client_->async_send_goal(goal_msg, send_goal_options);
  }

  void goal_response_callback(std::shared_future<rclcpp_action::ClientGoalHandle<example_action_msgs::action::Example>::SharedPtr> future)
  {
    auto goal_handle = future.get();
    if (!goal_handle) {
      RCLCPP_ERROR(this->get_logger(), "Goal was rejected by server");
      return;
    }
    RCLCPP_INFO(this->get_logger(), "Goal accepted by server, waiting for result");
  }

  void feedback_callback(
    rclcpp_action::ClientGoalHandle<example_action_msgs::action::Example>::SharedPtr,
    const std::shared_ptr<const example_action_msgs::action::Example::Feedback> feedback)
  {
    RCLCPP_INFO(this->get_logger(), "Current progress: %f", feedback->current_progress);
  }

  void result_callback(const rclcpp_action::ClientGoalHandle<example_action_msgs::action::Example>::WrappedResult & result)
  {
    switch (result.code) {
      case rclcpp_action::ResultCode::SUCCEEDED:
        RCLCPP_INFO(this->get_logger(), "Goal succeeded");
        break;
      case rclcpp_action::ResultCode::ABORTED:
        RCLCPP_ERROR(this->get_logger(), "Goal was aborted");
        return;
      case rclcpp_action::ResultCode::CANCELED:
        RCLCPP_ERROR(this->get_logger(), "Goal was canceled");
        return;
      default:
        RCLCPP_ERROR(this->get_logger(), "Unknown result code");
        return;
    }

    RCLCPP_INFO(this->get_logger(), "Result: %s", result.result->success ? "success" : "failure");
  }
};

위 코드에서는 액션 클라이언트를 구현하였다. 클라이언트는 목표를 설정하여 액션 서버로 전달하며, 서버로부터 피드백을 받아 처리한다. 작업이 완료되면 결과를 받아서 성공 또는 실패 여부를 확인한다. 멀티 액션 구조에서는 이러한 클라이언트가 여러 개의 서버와 동시에 통신할 수 있으며, 비동기적인 작업을 효과적으로 처리할 수 있다.

멀티 액션 구조에서의 동기화 문제

멀티 액션 구조에서 중요한 부분 중 하나는 동기화이다. 여러 액션이 동시에 실행될 경우, 특정 조건에서 이들이 서로 동기화되어야 할 수 있다. 예를 들어, 하나의 액션이 완료된 후 다른 액션이 실행되어야 하는 상황이 있을 수 있다.

이를 해결하기 위해서는 ROS2의 액션 서버 및 클라이언트 구조를 확장하여 액션 간의 상호작용을 관리할 수 있는 메커니즘을 도입해야 한다. 이를 구현하는 한 가지 방법은 각 액션의 상태를 추적하여, 특정 상태에 도달했을 때 다른 액션을 트리거하는 방식이다.

액션 상태 추적

각 액션은 여러 상태를 가질 수 있다. 이를 수식으로 나타내면 다음과 같다.

\mathbf{s}_i = \{ \text{Pending}, \text{Active}, \text{Succeeded}, \text{Aborted}, \text{Canceled} \}

여기서 \mathbf{s}_ii번째 액션의 상태이다. 멀티 액션 구조에서는 각 액션의 상태를 추적하여, 필요한 시점에 동기화 작업을 수행한다. 예를 들어, \mathbf{s}_1 = \text{Succeeded}일 때, \mathbf{s}_2를 활성화할 수 있다.

멀티 액션 구조에서의 상태 관리

멀티 액션 구조에서 각 액션의 상태를 관리하기 위해 상태 전이 모델을 적용할 수 있다. 각 액션은 다음과 같은 주요 상태를 갖는다.

\mathbf{s} = \{ \text{Pending}, \text{Active}, \text{Succeeded}, \text{Aborted}, \text{Canceled} \}

여기서, 상태 전이를 다음과 같이 정의할 수 있다:

  1. Pending: 액션이 시작되지 않았으며, 클라이언트가 목표를 설정한 상태.
  2. Active: 액션이 실행 중이며, 목표를 달성하려는 단계.
  3. Succeeded: 액션이 성공적으로 목표를 달성한 상태.
  4. Aborted: 액션이 오류로 인해 중단된 상태.
  5. Canceled: 클라이언트에 의해 취소된 상태.

멀티 액션 구조에서는 여러 액션의 상태를 동시에 관리해야 하므로, 상태 전이 메커니즘을 통해 각 액션이 독립적으로, 혹은 상호 의존적으로 처리되도록 설계한다.

상태 전이 다이어그램

멀티 액션 구조에서 각 액션이 어떻게 전이되는지를 상태 전이 다이어그램으로 나타낼 수 있다. 다음은 액션 상태 전이 예제이다.

stateDiagram [*] --> Pending Pending --> Active: Start Active --> Succeeded: Goal achieved Active --> Aborted: Error Active --> Canceled: Cancel requested Canceled --> [*] Succeeded --> [*] Aborted --> [*]

이 다이어그램에서 Pending에서 Active로 전환되고, Active 상태에서는 목표가 성공적으로 달성되면 Succeeded 상태로 전이된다. 오류가 발생하면 Aborted 상태로 전이되며, 클라이언트에서 취소 요청이 들어오면 Canceled 상태로 전이된다.

액션 간 동기화

멀티 액션 구조에서 여러 액션을 동시에 실행할 때, 액션 간의 동기화가 필요한 경우가 있다. 예를 들어, 하나의 액션이 완료된 후 다른 액션이 실행되거나, 특정 조건이 충족되었을 때 여러 액션이 동시에 실행되어야 하는 경우가 있다.

동기화 방법

동기화는 여러 가지 방법으로 구현할 수 있다. 그중 하나는 각 액션의 상태를 모니터링하여 특정 상태에 도달했을 때 다른 액션을 트리거하는 방식이다. 이를 구현하기 위해 ROS2에서 제공하는 상태 모니터링 메커니즘을 사용할 수 있다.

예를 들어, 두 개의 액션 A_1A_2가 있을 때, A_1이 완료되면 A_2가 시작되도록 설정할 수 있다. 이 과정은 다음과 같은 수식으로 표현된다:

\mathbf{s}_{A_2} = \text{Active} \quad \text{if} \quad \mathbf{s}_{A_1} = \text{Succeeded}

즉, 액션 A_2는 액션 A_1이 성공적으로 완료되었을 때 활성화된다. 이를 통해 액션 간의 순차적 동기화가 이루어질 수 있다.

병렬 액션 처리

멀티 액션 구조에서 여러 액션을 병렬로 처리할 수 있다. 병렬 처리의 경우, 각 액션은 독립적으로 실행되며 서로의 상태에 의존하지 않는다. 병렬 처리된 액션의 경우, 모든 액션이 완료될 때까지 기다리거나, 가장 먼저 완료된 액션에 맞춰 다음 단계를 진행할 수 있다.

병렬 액션 처리는 다음과 같은 방식으로 표현될 수 있다:

\mathbf{s}_{A_1}, \mathbf{s}_{A_2}, \mathbf{s}_{A_3} \quad \text{are all executed concurrently.}

즉, 각 액션 A_1, A_2, A_3는 동시에 실행되며, 서로의 상태에 영향을 받지 않는다. 이 경우, 모든 액션이 완료된 후 결과를 수집하여 최종 처리를 진행한다.

병렬 액션의 동기화

병렬 액션 구조에서 중요한 문제는 여러 액션이 서로 독립적으로 실행되지만, 최종적으로는 전체 시스템의 결과를 결정하는 데 있어 동기화가 필요할 수 있다는 점이다. 예를 들어, 3개의 액션 A_1, A_2, A_3가 동시에 실행된 후, 각 액션의 결과가 모두 도출된 시점에 다음 단계가 진행되어야 한다면, 각 액션의 완료 상태를 모니터링하여 전체 동기화가 이루어져야 한다.

이를 수식으로 표현하면 다음과 같다:

\mathbf{s}_{A_1} = \text{Succeeded}, \quad \mathbf{s}_{A_2} = \text{Succeeded}, \quad \mathbf{s}_{A_3} = \text{Succeeded}

이 조건이 만족되면 다음 단계를 실행할 수 있다. 이를 처리하는 방법은 다음과 같은 방식으로 설계할 수 있다.

병렬 액션의 상태 모니터링

액션 클라이언트에서 여러 개의 액션을 동시에 요청할 수 있으며, 각 액션의 상태를 모니터링하여 동기화 작업을 수행할 수 있다. 예를 들어, 모든 액션이 완료될 때까지 기다리는 코드 구조는 다음과 같이 작성될 수 있다.

void monitor_parallel_actions(std::vector<rclcpp_action::ClientGoalHandle<example_action_msgs::action::Example>::SharedPtr> goal_handles)
{
  for (auto & goal_handle : goal_handles) {
    while (goal_handle->get_status() != rclcpp_action::GoalStatus::STATUS_SUCCEEDED &&
           goal_handle->get_status() != rclcpp_action::GoalStatus::STATUS_ABORTED &&
           goal_handle->get_status() != rclcpp_action::GoalStatus::STATUS_CANCELED) {
      std::this_thread::sleep_for(std::chrono::milliseconds(100));  // 상태를 주기적으로 확인
    }
    if (goal_handle->get_status() == rclcpp_action::GoalStatus::STATUS_ABORTED) {
      RCLCPP_ERROR(rclcpp::get_logger("ActionMonitor"), "One of the actions aborted");
    }
  }
  RCLCPP_INFO(rclcpp::get_logger("ActionMonitor"), "All actions completed");
}

위 코드는 병렬로 실행된 여러 액션의 상태를 주기적으로 확인하여, 모든 액션이 완료될 때까지 대기하는 예시이다. 각 액션의 상태를 확인하여 완료되었는지 여부를 판단하고, 모든 액션이 완료되면 다음 단계를 진행한다.

액션 피드백 처리

병렬 액션에서 각 액션은 독립적으로 피드백을 전달한다. 피드백은 액션이 진행 중일 때 클라이언트로 전달되는 중간 정보로, 클라이언트는 이를 기반으로 진행 상황을 모니터링하거나 추가 작업을 수행할 수 있다.

멀티 액션 구조에서 병렬로 실행되는 여러 액션의 피드백을 동시에 처리해야 하는 경우가 있다. 이를 처리하기 위해 각 액션의 피드백을 별도로 수신하여 적절히 관리해야 한다.

피드백 콜백 처리

다음은 병렬 액션에서 각각의 피드백을 처리하는 코드 예시이다.

void feedback_callback(
  const rclcpp_action::ClientGoalHandle<example_action_msgs::action::Example>::SharedPtr goal_handle,
  const std::shared_ptr<const example_action_msgs::action::Example::Feedback> feedback)
{
  RCLCPP_INFO(this->get_logger(), "Action ID: %s, Progress: %f", goal_handle->get_goal_id().c_str(), feedback->current_progress);
}

이 콜백 함수는 각 액션의 피드백을 독립적으로 처리한다. 병렬로 실행되는 여러 액션의 피드백이 동시에 전달될 수 있으며, 이를 각각 적절히 처리하여 진행 상황을 추적할 수 있다.

비동기 액션 관리

멀티 액션 구조에서 여러 액션은 동시에 또는 순차적으로 실행되지만, 비동기 방식으로 작동할 수 있어야 한다. 비동기 액션 처리는 시스템의 유연성을 높여 주며, 클라이언트가 액션 서버와의 상호작용을 더 효율적으로 관리할 수 있게 한다.

ROS2에서는 비동기 방식으로 액션을 요청하고 피드백과 결과를 처리할 수 있다. 비동기 방식의 장점은 작업을 요청한 후 기다리지 않고 다른 작업을 병렬로 처리할 수 있다는 것이다.

비동기 액션 예시

다음은 비동기 방식으로 액션을 처리하는 예시이다.

void send_goal_async()
{
  auto goal_msg = example_action_msgs::action::Example::Goal();
  goal_msg.target = 100.0;

  auto send_goal_options = rclcpp_action::Client<example_action_msgs::action::Example>::SendGoalOptions();
  send_goal_options.goal_response_callback =
    std::bind(&ExampleActionClient::goal_response_callback, this, std::placeholders::_1);
  send_goal_options.feedback_callback =
    std::bind(&ExampleActionClient::feedback_callback, this, std::placeholders::_1, std::placeholders::_2);
  send_goal_options.result_callback =
    std::bind(&ExampleActionClient::result_callback, this, std::placeholders::_1);

  this->client_->async_send_goal(goal_msg, send_goal_options);
}

위 코드는 액션을 비동기적으로 요청하여 피드백과 결과를 처리하는 방법을 보여준다. 비동기 방식으로 액션을 요청하면 클라이언트는 액션의 결과를 기다리지 않고 다른 작업을 계속 진행할 수 있다.

멀티 액션 구조에서의 에러 처리

멀티 액션 구조에서 중요한 또 다른 부분은 에러 처리이다. 여러 액션을 병렬로 처리하는 경우, 각 액션이 독립적으로 실패할 수 있으며, 이러한 실패는 전체 시스템에 영향을 미칠 수 있다. 따라서 각 액션의 상태를 모니터링하고, 에러가 발생했을 때 이를 적절히 처리하는 메커니즘이 필요하다.

에러 처리 전략

에러 처리를 위한 대표적인 전략은 다음과 같다.

  1. 개별 액션 실패 허용: 하나의 액션이 실패하더라도 다른 액션들은 계속 실행된다.
  2. 전체 시스템 중단: 하나의 액션이 실패하면, 전체 시스템이 중단되고 나머지 액션들도 취소된다.
  3. 재시도: 실패한 액션을 재시도할 수 있는 로직을 추가하여 시스템의 회복력을 높인다.

에러 처리 코드 예시

에러가 발생했을 때 전체 시스템을 중단하는 방법을 구현한 예시는 다음과 같다.

void monitor_actions_with_error_handling(std::vector<rclcpp_action::ClientGoalHandle<example_action_msgs::action::Example>::SharedPtr> goal_handles)
{
  for (auto & goal_handle : goal_handles) {
    while (goal_handle->get_status() != rclcpp_action::GoalStatus::STATUS_SUCCEEDED &&
           goal_handle->get_status() != rclcpp_action::GoalStatus::STATUS_ABORTED &&
           goal_handle->get_status() != rclcpp_action::GoalStatus::STATUS_CANCELED) {
      std::this_thread::sleep_for(std::chrono::milliseconds(100));  // 상태를 주기적으로 확인
    }

    if (goal_handle->get_status() == rclcpp_action::GoalStatus::STATUS_ABORTED) {
      RCLCPP_ERROR(rclcpp::get_logger("ActionMonitor"), "One of the actions aborted. Canceling all actions.");
      for (auto & handle : goal_handles) {
        if (handle->get_status() == rclcpp_action::GoalStatus::STATUS_ACTIVE) {
          handle->cancel_goal();
        }
      }
      return;
    }
  }
  RCLCPP_INFO(rclcpp::get_logger("ActionMonitor"), "All actions completed successfully");
}

위 코드는 멀티 액션 구조에서 하나의 액션이 실패(Aborted)했을 때, 다른 모든 액션을 취소하는 로직을 보여준다. 이러한 방식으로 에러가 발생하면 시스템이 전체적으로 중단되며, 남아있는 액션들을 중단할 수 있다.

멀티 액션의 재시도

멀티 액션 구조에서는 특정 조건에서 실패한 액션을 다시 시도할 수 있도록 설계하는 것이 중요하다. 재시도는 시스템의 회복력을 높여주며, 네트워크 오류나 일시적인 장애로 인해 액션이 실패했을 때 유용하다.

재시도 구현

액션 재시도 로직은 실패한 액션이 특정 횟수만큼 재시도된 후에도 실패할 경우, 전체 시스템이 중단되는 방식으로 설계될 수 있다. 이를 위해서는 각 액션의 상태와 재시도 횟수를 추적해야 한다.

void monitor_actions_with_retry(std::vector<rclcpp_action::ClientGoalHandle<example_action_msgs::action::Example>::SharedPtr> goal_handles, int max_retries)
{
  for (auto & goal_handle : goal_handles) {
    int retry_count = 0;
    while (goal_handle->get_status() != rclcpp_action::GoalStatus::STATUS_SUCCEEDED &&
           goal_handle->get_status() != rclcpp_action::GoalStatus::STATUS_ABORTED &&
           goal_handle->get_status() != rclcpp_action::GoalStatus::STATUS_CANCELED) {
      std::this_thread::sleep_for(std::chrono::milliseconds(100));  // 상태를 주기적으로 확인
    }

    while (goal_handle->get_status() == rclcpp_action::GoalStatus::STATUS_ABORTED && retry_count < max_retries) {
      RCLCPP_INFO(rclcpp::get_logger("ActionMonitor"), "Retrying action (attempt %d)...", retry_count + 1);
      // 재시도 로직 (액션을 재요청)
      // ...
      retry_count++;
    }

    if (retry_count == max_retries) {
      RCLCPP_ERROR(rclcpp::get_logger("ActionMonitor"), "Action failed after maximum retries");
      return;
    }
  }
  RCLCPP_INFO(rclcpp::get_logger("ActionMonitor"), "All actions completed successfully or retried successfully");
}

위 코드는 멀티 액션 구조에서 재시도를 구현한 예시이다. 각 액션은 최대 max_retries만큼 재시도되며, 재시도 횟수를 초과하면 해당 액션은 실패로 처리된다.

멀티 액션 구조의 최적화

멀티 액션 구조에서 성능 최적화는 매우 중요하다. 특히 병렬로 실행되는 액션들이 많을수록 시스템 리소스가 많이 소비되기 때문에, 효율적으로 동작하도록 최적화할 필요가 있다.

성능 최적화를 위한 방법

  1. 멀티스레드 활용: 여러 액션을 동시에 처리하기 위해 멀티스레딩을 활용한다. 이를 통해 각 액션이 독립적으로 실행되고, 성능을 향상시킬 수 있다.
  2. 비동기 처리 최적화: 비동기 방식으로 액션을 처리하여, 블로킹 없이 작업을 수행할 수 있도록 설계한다.
  3. 자원 관리: 병렬 액션이 많을 경우 시스템 리소스를 효율적으로 사용하기 위한 자원 관리 전략을 도입해야 한다.

멀티스레딩을 활용한 성능 최적화

다음은 멀티스레딩을 활용하여 여러 액션을 병렬로 처리하는 예시이다.

void execute_action_in_thread(rclcpp_action::ClientGoalHandle<example_action_msgs::action::Example>::SharedPtr goal_handle)
{
  std::thread([goal_handle]() {
    while (goal_handle->get_status() != rclcpp_action::GoalStatus::STATUS_SUCCEEDED &&
           goal_handle->get_status() != rclcpp_action::GoalStatus::STATUS_ABORTED &&
           goal_handle->get_status() != rclcpp_action::GoalStatus::STATUS_CANCELED) {
      std::this_thread::sleep_for(std::chrono::milliseconds(100));
    }
    if (goal_handle->get_status() == rclcpp_action::GoalStatus::STATUS_SUCCEEDED) {
      RCLCPP_INFO(rclcpp::get_logger("ActionMonitor"), "Action succeeded");
    } else {
      RCLCPP_ERROR(rclcpp::get_logger("ActionMonitor"), "Action failed or was canceled");
    }
  }).detach();  // 별도의 스레드에서 실행
}

이 코드는 액션을 별도의 스레드에서 실행하여 비동기적으로 처리하는 방법을 보여준다. 각 액션은 독립적인 스레드에서 실행되므로, 병렬로 여러 액션을 동시에 처리할 수 있다.