7. Action Client 작성
파일 생성:
cd ~/ros2_study/src/my_cpp_package/
touch src/move_distance_client.cpp

내용:
#include <chrono>
#include <cstdlib>
#include <memory>
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_action/rclcpp_action.hpp"
#include "my_first_package_msgs/action/move_distance.hpp"
using namespace std::chrono_literals;
class MoveDistanceClient : public rclcpp::Node
{
public:
using MoveDistance = my_first_package_msgs::action::MoveDistance;
using GoalHandleMoveDistance = rclcpp_action::ClientGoalHandle<MoveDistance>;
MoveDistanceClient()
: Node("move_distance_client")
{
action_client_ = rclcpp_action::create_client<MoveDistance>(
this,
"move_distance"
);
}
void send_goal(float target_distance)
{
if (!action_client_->wait_for_action_server(5s)) {
RCLCPP_ERROR(this->get_logger(), "Action server not available.");
return;
}
auto goal_msg = MoveDistance::Goal();
goal_msg.target_distance = target_distance;
RCLCPP_INFO(
this->get_logger(),
"Sending goal: move %.2f meters",
target_distance
);
auto send_goal_options = rclcpp_action::Client<MoveDistance>::SendGoalOptions();
send_goal_options.goal_response_callback =
std::bind(&MoveDistanceClient::goal_response_callback, this, std::placeholders::_1);
send_goal_options.feedback_callback =
std::bind(
&MoveDistanceClient::feedback_callback,
this,
std::placeholders::_1,
std::placeholders::_2
);
send_goal_options.result_callback =
std::bind(&MoveDistanceClient::result_callback, this, std::placeholders::_1);
action_client_->async_send_goal(goal_msg, send_goal_options);
}
private:
rclcpp_action::Client<MoveDistance>::SharedPtr action_client_;
void goal_response_callback(const GoalHandleMoveDistance::SharedPtr & goal_handle)
{
if (!goal_handle) {
RCLCPP_ERROR(this->get_logger(), "Goal was rejected by server.");
} else {
RCLCPP_INFO(this->get_logger(), "Goal accepted by server.");
}
}
void feedback_callback(
GoalHandleMoveDistance::SharedPtr,
const std::shared_ptr<const MoveDistance::Feedback> feedback)
{
RCLCPP_INFO(
this->get_logger(),
"Feedback received: %.2f m, %.1f %%",
feedback->current_distance,
feedback->progress
);
}
void result_callback(const GoalHandleMoveDistance::WrappedResult & result)
{
switch (result.code) {
case rclcpp_action::ResultCode::SUCCEEDED:
RCLCPP_INFO(this->get_logger(), "Result: success");
break;
case rclcpp_action::ResultCode::ABORTED:
RCLCPP_ERROR(this->get_logger(), "Result: aborted");
rclcpp::shutdown();
return;
case rclcpp_action::ResultCode::CANCELED:
RCLCPP_WARN(this->get_logger(), "Result: canceled");
rclcpp::shutdown();
return;
default:
RCLCPP_ERROR(this->get_logger(), "Unknown result code");
rclcpp::shutdown();
return;
}
RCLCPP_INFO(
this->get_logger(),
"Message: %s",
result.result->message.c_str()
);
rclcpp::shutdown();
}
};
int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
float target_distance = 1.0;
if (argc >= 2) {
target_distance = std::atof(argv[1]);
}
auto action_client = std::make_shared<MoveDistanceClient>();
action_client->send_goal(target_distance);
rclcpp::spin(action_client);
return 0;
}

8. MoveDistance Action Client 소스 분석
1) 전체 역할
이 노드는 /move_distance Action Server에 접속한 뒤, 목표 이동 거리 값을 Goal로 전송합니다.
서버가 Goal을 수락하면 실행이 시작되고, 클라이언트는 실행 중 다음 정보를 계속 받습니다.
현재 이동 거리
진행률
서버가 목표 거리에 도달하면 최종 결과를 받아 출력하고 노드를 종료합니다.
전체 흐름은 다음과 같습니다.
1. Action Client 노드 실행
2. move_distance Action Server 대기
3. 목표 거리 Goal 생성
4. 서버로 Goal 전송
5. 서버의 Goal 수락 여부 확인
6. 실행 중 Feedback 수신
7. 최종 Result 수신
8. 노드 종료
2) 헤더 파일 포함
#include <chrono>
#include <cstdlib>
#include <memory>
표준 C++ 라이브러리입니다.
a. chrono
#include <chrono>
시간 관련 기능을 사용하기 위한 헤더입니다.
이 코드에서는 Action Server를 기다릴 때 다음처럼 사용합니다.
wait_for_action_server(5s)
즉, 최대 5초 동안 Action Server가 준비될 때까지 기다립니다.
b. cstdlib
#include <cstdlib>
문자열을 숫자로 변환하기 위해 사용합니다.
이 코드에서는 명령행 인자로 받은 문자열을 float 값으로 바꾸기 위해 사용합니다.
target_distance = std::atof(argv[1]);
예를 들어 터미널에서 다음처럼 실행하면,
ros2 run my_first_package move_distance_client 2.5
argv[1]에는 문자열 "2.5"가 들어오고, std::atof()를 통해 숫자 2.5로 변환됩니다.
c. memory
#include <memory>
std::shared_ptr를 사용하기 위한 헤더입니다.
ROS 2에서는 노드, Action Client, Goal Handle, Feedback, Result 등을 포인터 기반으로 관리하는 경우가 많습니다.
3) ROS 2 관련 헤더
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_action/rclcpp_action.hpp"
a. rclcpp
#include "rclcpp/rclcpp.hpp"
ROS 2 C++ 노드를 만들기 위한 기본 헤더입니다.
이 헤더를 통해 다음 기능을 사용할 수 있습니다.
rclcpp::Node
rclcpp::init()
rclcpp::spin()
rclcpp::shutdown()
RCLCPP_INFO()
RCLCPP_ERROR()
RCLCPP_WARN()
b. rclcpp_action
#include "rclcpp_action/rclcpp_action.hpp"
ROS 2 Action Client를 만들기 위한 헤더입니다.
이 코드에서는 다음과 같은 Action 관련 기능을 사용합니다.
rclcpp_action::create_client
rclcpp_action::Client
rclcpp_action::ClientGoalHandle
rclcpp_action::ResultCode
#include "my_first_package_msgs/action/move_distance.hpp"
사용자가 직접 정의한 MoveDistance.action 인터페이스를 포함합니다.
이 헤더를 포함하면 C++ 코드에서 다음 타입을 사용할 수 있습니다.
MoveDistance::Goal
MoveDistance::Result
MoveDistance::Feedback
5) 시간 리터럴 사용
using namespace std::chrono_literals;
이 선언을 사용하면 시간 값을 다음처럼 간단히 표현할 수 있습니다.
5s
100ms
1min
이 코드에서는 다음 부분에서 사용됩니다.
action_client_->wait_for_action_server(5s)
즉, Action Server를 최대 5초 동안 기다린다는 의미입니다.
6) 클래스 선언
class MoveDistanceClient : public rclcpp::Node
MoveDistanceClient 클래스는 ROS 2 노드 클래스입니다.
rclcpp::Node를 상속받기 때문에 이 클래스는 ROS 2 노드로 동작할 수 있습니다.
노드 이름은 생성자에서 다음과 같이 설정됩니다.
Node("move_distance_client")
실행 후 노드 목록을 확인하면 다음처럼 표시될 수 있습니다.
ros2 node list
출력 예:
/move_distance_client
7) Action 타입 별칭 선언
using MoveDistance = my_first_package_msgs::action::MoveDistance;
using GoalHandleMoveDistance = rclcpp_action::ClientGoalHandle<MoveDistance>;
코드를 짧고 읽기 쉽게 만들기 위한 타입 별칭입니다.
a. MoveDistance
using MoveDistance = my_first_package_msgs::action::MoveDistance;
원래 Action 타입 이름은 다음처럼 깁니다.
my_first_package_msgs::action::MoveDistance
이를 매번 쓰면 코드가 길어지므로 MoveDistance라는 짧은 이름으로 바꿔 사용합니다.
이후 코드에서는 다음처럼 사용할 수 있습니다.
MoveDistance::Goal
MoveDistance::Feedback
MoveDistance::Result
b. GoalHandleMoveDistance
using GoalHandleMoveDistance = rclcpp_action::ClientGoalHandle<MoveDistance>;
클라이언트 쪽 Goal Handle 타입입니다.
Goal Handle은 클라이언트가 보낸 Goal의 상태를 관리하는 객체입니다.
클라이언트는 Goal Handle을 통해 서버가 Goal을 수락했는지, 실행 중인지, 취소되었는지 등을 추적할 수 있습니다.
이 코드에서는 주로 콜백 함수의 인자로 사용됩니다.
8) 생성자
MoveDistanceClient()
: Node("move_distance_client")
{
action_client_ = rclcpp_action::create_client<MoveDistance>(
this,
"move_distance"
);
}
생성자에서는 ROS 2 노드 이름을 설정하고, Action Client를 생성합니다.
a. 노드 이름 설정
Node("move_distance_client")
현재 노드의 이름을 move_distance_client로 설정합니다.
b. Action Client 생성
action_client_ = rclcpp_action::create_client<MoveDistance>(
this,
"move_distance"
);
MoveDistance 타입의 Action Client를 생성합니다.
첫 번째 인자:
this
현재 노드에 Action Client를 생성한다는 의미입니다.
두 번째 인자:
"move_distance"
접속할 Action 이름입니다.
즉, 이 클라이언트는 /move_distance라는 이름의 Action Server와 통신합니다.
앞에서 만든 서버 코드에서도 다음처럼 Action Server 이름을 지정했습니다.
"move_distance"
따라서 서버와 클라이언트의 Action 이름이 반드시 같아야 합니다.
9) Action Client 멤버 변수
rclcpp_action::Client<MoveDistance>::SharedPtr action_client_;
Action Client 객체를 저장하는 멤버 변수입니다.
이 객체를 통해 다음 작업을 수행합니다.
wait_for_action_server()
async_send_goal()
즉, action_client_는 Action Server에 Goal을 보내는 핵심 객체입니다.
10) send_goal 함수
void send_goal(float target_distance)
이 함수는 Action Server로 목표 거리를 보내는 함수입니다.
인자로 받은 target_distance 값이 서버에 Goal로 전달됩니다.
예를 들어 다음처럼 호출되면,
send_goal(1.0);
서버에는 1.0m 이동하라는 Goal이 전송됩니다.
11) Action Server 대기
if (!action_client_->wait_for_action_server(5s)) {
RCLCPP_ERROR(this->get_logger(), "Action server not available.");
return;
}
Goal을 보내기 전에 Action Server가 실행 중인지 확인합니다.
a. wait_for_action_server()
action_client_->wait_for_action_server(5s)
move_distance Action Server가 준비될 때까지 최대 5초 동안 기다립니다.
서버가 5초 안에 발견되면 true를 반환합니다.
서버가 없으면 false를 반환합니다.
b. 서버가 없을 때
RCLCPP_ERROR(this->get_logger(), "Action server not available.");
return;
Action Server가 실행 중이 아니면 에러 로그를 출력하고 함수를 종료합니다.
즉, Goal을 보내지 않습니다.
이 경우 먼저 서버 노드를 실행해야 합니다.
ros2 run my_first_package move_distance_server
그 다음 클라이언트를 실행해야 정상적으로 동작합니다.
12) Goal 메시지 생성
auto goal_msg = MoveDistance::Goal();
goal_msg.target_distance = target_distance;
Action Server에 보낼 Goal 메시지를 생성합니다.
a. Goal 객체 생성
auto goal_msg = MoveDistance::Goal();
MoveDistance.action 파일의 Goal 부분에 해당하는 메시지 객체를 생성합니다.
b. 목표 거리 값 설정
goal_msg.target_distance = target_distance;
Goal 메시지 안의 target_distance 필드에 목표 이동 거리를 저장합니다.
예를 들어 target_distance가 2.0이면 서버에는 다음 Goal이 전송됩니다.
target_distance = 2.0
13) Goal 전송 로그
RCLCPP_INFO(
this->get_logger(),
"Sending goal: move %.2f meters",
target_distance
);
클라이언트가 서버로 보낼 목표 거리를 로그로 출력합니다.
출력 예:
Sending goal: move 1.00 meters
14) SendGoalOptions 생성
auto send_goal_options = rclcpp_action::Client<MoveDistance>::SendGoalOptions();
Action Goal을 보낼 때 사용할 옵션 객체를 생성합니다.
SendGoalOptions에는 Goal 전송 후 호출될 콜백 함수들을 등록합니다.
이 코드에서는 다음 3개의 콜백을 등록합니다.
goal_response_callback
feedback_callback
result_callback
각 콜백의 역할은 다음과 같습니다.
| goal_response_callback() | 서버가 Goal을 수락/거절했을 때 | Goal 수락 여부 확인 |
| feedback_callback() | 서버가 Feedback을 보낼 때마다 | 진행 상태 확인 |
| result_callback() | Action이 완료되었을 때 | 최종 결과 확인 |
15) Goal Response 콜백 등록
send_goal_options.goal_response_callback =
std::bind(&MoveDistanceClient::goal_response_callback, this, std::placeholders::_1);
서버가 Goal을 수락했는지 거절했는지 확인하는 콜백 함수를 등록합니다.
a. std::bind()
std::bind(&MoveDistanceClient::goal_response_callback, this, std::placeholders::_1)
클래스 멤버 함수인 goal_response_callback()을 콜백으로 등록하기 위해 사용합니다.
std::placeholders::_1은 나중에 콜백이 호출될 때 전달되는 첫 번째 인자를 의미합니다.
즉, 서버의 Goal 응답 결과가 _1 자리에 들어옵니다.
16) Feedback 콜백 등록
send_goal_options.feedback_callback =
std::bind(
&MoveDistanceClient::feedback_callback,
this,
std::placeholders::_1,
std::placeholders::_2
);
서버가 Feedback을 보낼 때마다 호출될 콜백 함수를 등록합니다.
Feedback 콜백은 인자를 2개 받습니다.
GoalHandleMoveDistance::SharedPtr
std::shared_ptr<const MoveDistance::Feedback>
그래서 std::placeholders::_1, std::placeholders::_2를 사용합니다. current_distance와 progess입니다.
17) Result 콜백 등록
send_goal_options.result_callback =
std::bind(&MoveDistanceClient::result_callback, this, std::placeholders::_1);
Action이 끝났을 때 호출될 콜백 함수를 등록합니다.
서버가 succeed(), canceled(), abort() 중 하나로 Action을 종료하면 이 콜백이 호출됩니다.
18) Goal 비동기 전송
action_client_->async_send_goal(goal_msg, send_goal_options);
Action Server에 Goal을 전송합니다.
여기서 중요한 점은 async_send_goal()이라는 이름입니다.
async는 비동기라는 뜻입니다. 즉, 이 함수는 Goal을 보내고 서버의 최종 결과가 올 때까지 기다리지 않습니다.
대신 등록해 둔 콜백 함수들이 나중에 자동으로 호출됩니다.
실행 흐름은 다음과 같습니다.
async_send_goal() 호출
↓
Goal 서버로 전송
↓
서버가 수락 또는 거절
↓
goal_response_callback() 호출
↓
서버 실행 중 Feedback 전송
↓
feedback_callback() 반복 호출
↓
서버 실행 완료
↓
result_callback() 호출
19) goal_response_callback 함수
void goal_response_callback(const GoalHandleMoveDistance::SharedPtr & goal_handle)
{
if (!goal_handle) {
RCLCPP_ERROR(this->get_logger(), "Goal was rejected by server.");
} else {
RCLCPP_INFO(this->get_logger(), "Goal accepted by server.");
}
}
이 함수는 서버가 Goal을 수락했는지 거절했는지 확인합니다.
a. Goal이 거절된 경우
if (!goal_handle)
Goal Handle이 비어 있으면 서버가 Goal을 거절했다는 의미입니다.
예를 들어 서버 코드에서 다음 조건이 있었습니다.
if (goal->target_distance <= 0.0) {
return rclcpp_action::GoalResponse::REJECT;
}
따라서 클라이언트가 목표 거리로 0 또는 음수를 보내면 서버는 Goal을 거절합니다.
이때 클라이언트에는 다음 로그가 출력됩니다.
Goal was rejected by server.
b. Goal이 수락된 경우
else {
RCLCPP_INFO(this->get_logger(), "Goal accepted by server.");
}
Goal Handle이 정상적으로 존재하면 서버가 Goal을 수락했다는 뜻입니다.
이후 서버는 목표 거리 이동 작업을 실행하고 Feedback을 보내기 시작합니다.
20) feedback_callback 함수
void feedback_callback(
GoalHandleMoveDistance::SharedPtr,
const std::shared_ptr<const MoveDistance::Feedback> feedback)
이 함수는 Action Server가 Feedback을 보낼 때마다 호출됩니다.
a. 첫 번째 인자
GoalHandleMoveDistance::SharedPtr
첫 번째 인자는 Goal Handle입니다.
현재 코드에서는 사용하지 않기 때문에 변수 이름을 생략했습니다.
GoalHandleMoveDistance::SharedPtr,
이런 식으로 타입만 적고 변수 이름을 적지 않으면, 사용하지 않는 인자라는 의미가 됩니다.
b. 두 번째 인자
const std::shared_ptr<const MoveDistance::Feedback> feedback
서버가 보내준 Feedback 메시지입니다.
이 메시지 안에는 다음 값이 들어 있습니다.
feedback->current_distance
feedback->progress
c. Feedback 로그 출력
RCLCPP_INFO(
this->get_logger(),
"Feedback received: %.2f m, %.1f %%",
feedback->current_distance,
feedback->progress
);
서버로부터 받은 현재 이동 거리와 진행률을 출력합니다.
예를 들어 목표 거리가 1.0m이고 서버가 0.1m씩 증가시키면 다음과 같이 출력될 수 있습니다.
Feedback received: 0.10 m, 10.0 %
Feedback received: 0.20 m, 20.0 %
Feedback received: 0.30 m, 30.0 %
...
Feedback received: 1.00 m, 100.0 %
여기서 %%는 % 문자를 출력하기 위한 표현입니다.
C/C++ 포맷 문자열에서 %는 특별한 의미를 가지므로, 실제 % 기호를 출력하려면 %%라고 작성해야 합니다.
21) result_callback 함수
void result_callback(const GoalHandleMoveDistance::WrappedResult & result)
이 함수는 Action Server가 최종 Result를 보냈을 때 호출됩니다.
즉, Action 작업이 끝났을 때 실행됩니다.
a. WrappedResult
GoalHandleMoveDistance::WrappedResult
WrappedResult는 단순히 Result 메시지만 가지고 있는 것이 아니라, Action의 종료 상태 코드까지 함께 가지고 있습니다.
주요 구성은 다음과 같습니다.
result.code
result.result
| result.code | Action 종료 상태 |
| result.result | 서버가 보낸 Result 메시지 |
22) Result 상태 코드 확인
switch (result.code) {
Action이 어떤 상태로 끝났는지 확인합니다.
ROS 2 Action의 대표적인 종료 상태는 다음과 같습니다.
| SUCCEEDED | 성공적으로 완료 |
| ABORTED | 서버 측에서 중단 |
| CANCELED | 취소됨 |
a. 성공한 경우
case rclcpp_action::ResultCode::SUCCEEDED:
RCLCPP_INFO(this->get_logger(), "Result: success");
break;
서버가 Goal을 성공 상태로 완료한 경우입니다.
서버 코드에서는 목표 거리에 도달했을 때 다음 함수를 호출했습니다.
goal_handle->succeed(result);
이 경우 클라이언트의 result.code는 다음 값이 됩니다.
rclcpp_action::ResultCode::SUCCEEDED
클라이언트 로그:
Result: success
b. 중단된 경우
case rclcpp_action::ResultCode::ABORTED:
RCLCPP_ERROR(this->get_logger(), "Result: aborted");
rclcpp::shutdown();
return;
서버가 작업을 강제로 중단한 경우입니다.
예를 들어 실무 코드에서는 다음과 같은 상황에서 abort()를 사용할 수 있습니다.
모터 제어 실패
센서 데이터 이상
장애물 감지
목표 도달 불가능
내부 에러 발생
현재 서버 코드에는 abort() 처리가 없으므로 일반적으로 이 상태는 발생하지 않습니다.
하지만 실무 코드를 생각하면 반드시 처리해 두는 것이 좋습니다.
c. 취소된 경우
case rclcpp_action::ResultCode::CANCELED:
RCLCPP_WARN(this->get_logger(), "Result: canceled");
rclcpp::shutdown();
return;
Action이 취소된 경우입니다.
서버 코드에서 취소 요청을 처리하면 다음 함수를 호출했습니다.
goal_handle->canceled(result);
이 경우 클라이언트의 result.code는 다음 값이 됩니다.
rclcpp_action::ResultCode::CANCELED
클라이언트 로그:
Result: canceled
d. 알 수 없는 상태
default:
RCLCPP_ERROR(this->get_logger(), "Unknown result code");
rclcpp::shutdown();
return;
위에서 처리하지 않은 상태 코드가 들어온 경우입니다.
예외적인 상황이므로 에러 로그를 출력하고 노드를 종료합니다.
23) Result 메시지 출력
RCLCPP_INFO(
this->get_logger(),
"Message: %s",
result.result->message.c_str()
);
서버가 보낸 최종 Result 메시지를 출력합니다.
서버 코드에서는 성공 시 다음 메시지를 보냈습니다.
result->message = "Target distance reached.";
따라서 성공한 경우 클라이언트는 다음 로그를 출력합니다.
Message: Target distance reached.
a. c_str()을 사용하는 이유
result.result->message.c_str()
result.result->message는 C++의 std::string 타입입니다.
하지만 RCLCPP_INFO()의 포맷 문자열 %s는 C 스타일 문자열을 요구합니다.
그래서 std::string을 C 문자열 포인터로 변환하기 위해 .c_str()을 사용합니다.
24) Result 수신 후 노드 종료
rclcpp::shutdown();
최종 Result를 받으면 ROS 2 시스템을 종료합니다.
이 코드에서는 한 번 Goal을 보내고 결과를 받은 뒤 바로 종료하는 구조입니다.
즉, 계속 여러 Goal을 보내는 클라이언트가 아니라, 한 번 실행하고 끝나는 테스트용 Action Client입니다.
25) main 함수
int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
float target_distance = 1.0;
if (argc >= 2) {
target_distance = std::atof(argv[1]);
}
auto action_client = std::make_shared<MoveDistanceClient>();
action_client->send_goal(target_distance);
rclcpp::spin(action_client);
return 0;
}
ROS 2 노드를 실행하는 메인 함수입니다.
a. ROS 2 초기화
rclcpp::init(argc, argv);
ROS 2 통신 시스템을 초기화합니다.
모든 ROS 2 노드는 실행 전에 반드시 rclcpp::init()을 호출해야 합니다.
b. 기본 목표 거리 설정
float target_distance = 1.0;
기본 목표 거리를 1.0m로 설정합니다.
즉, 실행할 때 별도의 인자를 주지 않으면 클라이언트는 서버에 1.0m 이동 Goal을 보냅니다.
c. 명령행 인자 확인
if (argc >= 2) {
target_distance = std::atof(argv[1]);
}
프로그램 실행 시 목표 거리를 인자로 받을 수 있습니다.
예를 들어 다음처럼 실행하면,
ros2 run my_first_package move_distance_client 3.5
argv[1]에는 문자열 "3.5"가 들어옵니다.
이를 std::atof()로 변환하면 target_distance는 3.5가 됩니다.
결과적으로 서버에는 다음 Goal이 전송됩니다.
target_distance = 3.5
d. Action Client 노드 생성
auto action_client = std::make_shared<MoveDistanceClient>();
MoveDistanceClient 객체를 생성합니다.
객체가 생성되면 생성자에서 Action Client도 함께 생성됩니다.
action_client_ = rclcpp_action::create_client<MoveDistance>(
this,
"move_distance"
);
e. Goal 전송
action_client->send_goal(target_distance);
서버로 목표 거리 Goal을 전송합니다.
이 함수 내부에서 다음 작업이 진행됩니다.
1. Action Server 대기
2. Goal 메시지 생성
3. 콜백 함수 등록
4. async_send_goal() 호출
f. 노드 실행
rclcpp::spin(action_client);
노드를 계속 실행 상태로 유지합니다.
이 부분이 매우 중요합니다.
async_send_goal()은 비동기 방식이기 때문에, Goal 전송 후 콜백 함수들이 호출되려면 rclcpp::spin()이 실행되고 있어야 합니다.
즉, 다음 콜백들은 spin()이 동작 중일 때 호출됩니다.
goal_response_callback()
feedback_callback()
result_callback()
만약 spin()을 호출하지 않으면 Goal을 보낸 뒤 콜백 처리가 제대로 되지 않을 수 있습니다.
9. my_cpp_package 설정
1) package.xml
my_cpp_package/package.xml에 다음 의존성이 있는지 확인합니다.
<depend>rclcpp</depend>
<depend>rclcpp_action</depend>
<depend>my_first_package_msgs</depend>
예시:
<?xml version="1.0"?>
<package format="3">
<name>my_cpp_package</name>
<version>0.0.0</version>
<description>C++ action server and client practice package</description>
<maintainer email="user@example.com">user</maintainer>
<license>Apache-2.0</license>
<buildtool_depend>ament_cmake</buildtool_depend>
<depend>rclcpp</depend>
<depend>rclcpp_action</depend>
<depend>my_first_package_msgs</depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>

2) CMakeLists.txt
my_cpp_package/CMakeLists.txt를 다음처럼 수정합니다.
cmake_minimum_required(VERSION 3.8)
project(my_cpp_package)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_action REQUIRED)
find_package(my_first_package_msgs REQUIRED)
add_executable(move_distance_server src/move_distance_server.cpp)
ament_target_dependencies(move_distance_server rclcpp rclcpp_action my_first_package_msgs)
add_executable(move_distance_client src/move_distance_client.cpp)
ament_target_dependencies(move_distance_client rclcpp rclcpp_action my_first_package_msgs)
install(TARGETS
move_distance_server
move_distance_client
DESTINATION lib/${PROJECT_NAME}
)
ament_package()

10. 빌드하기
cd ~/ros2_ws
colcon build --packages-select my_first_package_msgs
source install/setup.bash
colcon build --packages-select my_cpp_package
source install/setup.bash
전체 빌드는 다음처럼 해도 됩니다.
cd ~/ros2_ws
colcon build
source install/setup.bash

11. Action 인터페이스 확인
ros2 interface show my_first_package_msgs/action/MoveDistance
예상 출력:
float32 target_distance
---
bool success
string message
---
float32 current_distance
float32 progress

12. 실행하기
터미널 1: Action Server 실행
cd ~/ros2_ws
source install/setup.bash
ros2 run my_cpp_package move_distance_server
예상 출력:
[INFO] [move_distance_server]: Move Distance Action Server started.

터미널 2: Action Client 실행
cd ~/ros2_ws
source install/setup.bash
ros2 run my_cpp_package move_distance_client 2.0
예상 출력:
[INFO] [move_distance_client]: Sending goal: move 2.00 meters
[INFO] [move_distance_client]: Goal accepted by server.
[INFO] [move_distance_client]: Feedback received: 0.10 m, 5.0 %
[INFO] [move_distance_client]: Feedback received: 0.20 m, 10.0 %
...
[INFO] [move_distance_client]: Result: success
[INFO] [move_distance_client]: Message: Target distance reached.

13. ROS 2 CLI로 Action 확인하기
액션 목록 확인
ros2 action list
예상 출력:
/move_distance

액션 타입 확인
ros2 action info /move_distance

CLI로 goal 보내기
클라이언트 노드 없이 CLI에서도 goal을 보낼 수 있습니다.
ros2 action send_goal /move_distance my_first_package_msgs/action/MoveDistance "{target_distance: 1.5}"

feedback까지 보고 싶으면 다음처럼 실행합니다.
ros2 action send_goal /move_distance my_first_package_msgs/action/MoveDistance "{target_distance: 1.5}" --feedback


14. 모바일 로봇과 연결하는 방향
현재 예제는 실제 바퀴를 움직이지 않고 가상의 이동 거리를 증가시키는 방식입니다.
실제 모바일 로봇에 연결하려면 서버의 execute() 함수 안에서 다음 기능을 추가하면 됩니다.
geometry_msgs::msg::Twist cmd_vel;
cmd_vel.linear.x = 0.2;
cmd_vel.angular.z = 0.0;
cmd_vel_pub_->publish(cmd_vel);
그리고 이동 거리는 단순 누적값 대신 /odom 토픽에서 받아 계산하는 것이 정석입니다.
실전 구조는 다음과 같습니다.
Action Client
|
| 목표 거리 요청
v
MoveDistance Action Server
|
| /cmd_vel 발행
v
Mobile Robot
|
| /odom 피드백
v
MoveDistance Action Server
|
| 진행률 feedback
v
Action Client
'강좌 > ROS2' 카테고리의 다른 글
| ROS 2 C++ 실행 인자 사용하기 (0) | 2026.05.15 |
|---|---|
| ROS 2 C++ 파라미터 실습 (0) | 2026.05.15 |
| ROS 2 C++ 서비스 프로그래밍 이해하기 (0) | 2026.05.15 |
| ROS 2 C++ 토픽 통신 기초: 센서 데이터를 보내고 받는 퍼블리셔와 서브스크라이버 만들기 (0) | 2026.05.15 |
| ROS2 launch 작성 (0) | 2026.05.10 |