ROS 2 노드를 만들다 보면 같은 프로그램이라도 실행할 때마다 다른 조건으로 동작시켜야 할 때가 있습니다.
예를 들어 모바일 로봇의 이동 속도를 바꾸거나, 반복 횟수를 다르게 주거나, 테스트 모드로 실행해야 할 수 있습니다.
이때 사용할 수 있는 대표적인 방법이 실행 인자(command line arguments) 입니다.
C++ 프로그램은 실행될 때 main() 함수에서 외부 입력값을 받을 수 있습니다.
int main(int argc, char * argv[])
여기서 argc는 실행 시 전달된 인자의 개수이고, argv는 각 인자가 문자열 형태로 저장된 배열입니다.
예를 들어 다음과 같이 실행하면,
./my_program -s 1.5 -c 3
프로그램은 -s, 1.5, -c, 3 같은 값을 문자열 인자로 받습니다.
ROS 2 Humble에서도 이 구조는 그대로 사용할 수 있습니다.
1. 실습 상황
이번 예제에서는 모바일 로봇의 간단한 순찰 동작을 가정합니다.
패키지는 이미 생성되어 있다고 했으므로, 다음 패키지를 기준으로 진행합니다.
~/ros2_study/src/my_cpp_package
예제 노드 이름은 다음과 같이 사용합니다.
patrol_node
이 노드는 실행 시 다음 값을 입력받는다고 가정합니다.
-s : 모바일 로봇 이동 속도 설정
-c : 반복 횟수 설정
-h : 도움말 출력
실행 예시는 다음과 같습니다.
ros2 run my_cpp_package patrol_node -s 1.2 -c 3
이 명령은 모바일 로봇의 이동 속도를 1.2, 반복 횟수를 3으로 설정해 노드를 실행한다는 의미입니다.
2. 소스 코드
my_cpp_package/src/에 patrol_node.cpp 파일을 만듭니다.

code를 실행하여 아래의 소스를 작성합니다.
#include <cstdio>
#include <cstdlib>
#include <memory>
#include <string>
#include "rclcpp/rclcpp.hpp"
#include "rcutils/cmdline_parser.h"
class PatrolNode : public rclcpp::Node
{
public:
PatrolNode(double speed, int count)
: Node("patrol_node"),
speed_(speed),
count_(count)
{
RCLCPP_INFO(this->get_logger(), "Patrol node started.");
RCLCPP_INFO(this->get_logger(), "Mobile robot speed: %.2f", speed_);
RCLCPP_INFO(this->get_logger(), "Repeat count: %d", count_);
}
private:
double speed_;
int count_;
};
void print_help()
{
printf("Usage:\n");
printf(" ros2 run my_cpp_package patrol_node [options]\n\n");
printf("Options:\n");
printf(" -h Show help message\n");
printf(" -s <speed> Set mobile robot speed. Default: 0.5\n");
printf(" -c <count> Set repeat count. Default: 1\n");
}
int main(int argc, char * argv[])
{
if (rcutils_cli_option_exist(argv, argv + argc, "-h")) {
print_help();
return 0;
}
rclcpp::init(argc, argv);
double speed = 0.5;
int count = 1;
char * speed_option = rcutils_cli_get_option(argv, argv + argc, "-s");
if (speed_option != nullptr) {
speed = std::stod(speed_option);
}
char * count_option = rcutils_cli_get_option(argv, argv + argc, "-c");
if (count_option != nullptr) {
count = std::stoi(count_option);
}
auto node = std::make_shared<PatrolNode>(speed, count);
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}

3. 소스 코드 분석
1) 헤더 파일 포함
#include <cstdio>
#include <cstdlib>
#include <memory>
#include <string>
기본 C++ 기능을 사용하기 위한 헤더입니다.
printf() 출력, 문자열 처리, 스마트 포인터 사용을 위해 포함합니다.
#include "rclcpp/rclcpp.hpp"
#include "rcutils/cmdline_parser.h"
rclcpp는 ROS 2 C++ 노드를 만들기 위한 핵심 라이브러리입니다.
rcutils/cmdline_parser.h는 실행 인자를 처리하기 위해 사용합니다.
예를 들어 -s, -c, -h 같은 옵션을 확인할 수 있습니다.
2) PatrolNode 클래스
class PatrolNode : public rclcpp::Node
PatrolNode는 ROS 2 노드 클래스입니다.
rclcpp::Node를 상속받아 ROS 2 노드로 동작합니다.
PatrolNode(double speed, int count)
: Node("patrol_node"),
speed_(speed),
count_(count)
생성자에서는 노드 이름을 patrol_node로 설정합니다.
그리고 실행 인자로 받은 speed와 count 값을 클래스 내부 변수에 저장합니다.
RCLCPP_INFO(this->get_logger(), "Patrol node started.");
RCLCPP_INFO(this->get_logger(), "Mobile robot speed: %.2f", speed_);
RCLCPP_INFO(this->get_logger(), "Repeat count: %d", count_);
노드가 실행되면 현재 설정된 모바일 로봇 속도와 반복 횟수를 출력합니다.
3) 도움말 출력 함수
void print_help()
이 함수는 사용 방법을 출력합니다.
printf(" ros2 run my_cpp_package patrol_node [options]\n\n");
사용자가 어떤 형식으로 노드를 실행해야 하는지 보여줍니다.
printf(" -s <speed> Set mobile robot speed. Default: 0.5\n");
printf(" -c <count> Set repeat count. Default: 1\n");
-s 옵션은 모바일 로봇의 속도를 설정합니다.
-c 옵션은 반복 횟수를 설정합니다.
4) main 함수 시작
int main(int argc, char * argv[])
C++ 프로그램의 시작점입니다.
argc와 argv를 통해 실행 시 입력된 인자들을 받을 수 있습니다.
예를 들어 다음 명령을 실행하면,
ros2 run my_cpp_package patrol_node -s 1.2 -c 3
argv 안에는 -s, 1.2, -c, 3 같은 값이 문자열로 들어갑니다.
5) -h 옵션 확인
if (rcutils_cli_option_exist(argv, argv + argc, "-h")) {
print_help();
return 0;
}
실행 인자 중에 -h가 있는지 확인합니다.
ros2 run my_cpp_package patrol_node -h
위처럼 실행하면 노드는 실행하지 않고 도움말만 출력한 뒤 종료됩니다.
6) ROS 2 초기화
rclcpp::init(argc, argv);
ROS 2 노드를 사용하기 전에 반드시 호출해야 하는 함수입니다.
이 코드가 실행되어야 ROS 2 시스템과 연결된 노드를 생성할 수 있습니다.
7) 기본값 설정
double speed = 0.5;
int count = 1;
사용자가 실행 인자를 입력하지 않았을 때 사용할 기본값입니다.
즉, 옵션 없이 실행하면 속도는 0.5, 반복 횟수는 1로 설정됩니다.
8) 속도 옵션 읽기
char * speed_option = rcutils_cli_get_option(argv, argv + argc, "-s");
-s 옵션 뒤에 입력된 값을 가져옵니다.
ros2 run my_cpp_package patrol_node -s 1.2
위 명령에서는 "1.2"가 문자열로 읽힙니다.
speed = std::stod(speed_option);
읽어온 문자열을 double 숫자 값으로 변환합니다.
9) 반복 횟수 옵션 읽기
char * count_option = rcutils_cli_get_option(argv, argv + argc, "-c");
-c 옵션 뒤에 입력된 값을 가져옵니다.
ros2 run my_cpp_package patrol_node -c 3
위 명령에서는 "3"이 문자열로 읽힙니다.
count = std::stoi(count_option);
읽어온 문자열을 int 숫자 값으로 변환합니다.
10) 노드 생성 및 실행
auto node = std::make_shared<PatrolNode>(speed, count);
앞에서 설정한 speed와 count 값을 이용해 PatrolNode 객체를 생성합니다.
rclcpp::spin(node);
노드를 계속 실행 상태로 유지합니다.
현재 예제에서는 별도의 반복 동작은 없지만, ROS 2 노드는 일반적으로 spin()을 통해 실행 상태를 유지합니다.
11) ROS 2 종료
rclcpp::shutdown();
노드 실행이 끝나면 ROS 2를 정상적으로 종료합니다.
4. CMakeLists.txt 수정
패키지가 이미 생성되어 있으므로 실행 파일만 추가하면 됩니다.
my_cpp_package/CMakeLists.txt에 다음 내용을 추가합니다.
add_executable(patrol_node src/patrol_node.cpp)
ament_target_dependencies(patrol_node rclcpp)
install(TARGETS
patrol_node
DESTINATION lib/${PROJECT_NAME}
)
전체 파일에서 ament_package()는 가장 아래쪽에 있어야 합니다.

5. 빌드하기
workspace는 ros2_study입니다.
cd ~/ros2_study
colcon build --packages-select my_cpp_package
source install/setup.bash
빌드 후에는 반드시 source install/setup.bash를 실행해야 합니다.
이 과정을 하지 않으면 ros2 run 명령에서 새로 만든 실행 파일을 찾지 못할 수 있습니다.

6. 실행하기
기본값으로 실행합니다.
ros2 run my_cpp_package patrol_node
예상 출력은 다음과 비슷합니다.
[INFO] [patrol_node]: Patrol node started.
[INFO] [patrol_node]: Mobile robot speed: 0.50
[INFO] [patrol_node]: Repeat count: 1

속도와 반복 횟수를 지정해서 실행합니다.
ros2 run my_cpp_package patrol_node -s 1.2 -c 3
예상 출력은 다음과 같습니다.
[INFO] [patrol_node]: Patrol node started.
[INFO] [patrol_node]: Mobile robot speed: 1.20
[INFO] [patrol_node]: Repeat count: 3

도움말을 확인하려면 다음과 같이 실행합니다.
ros2 run my_cpp_package patrol_node -h
출력 예시는 다음과 같습니다.
Usage:
ros2 run my_cpp_package patrol_node [options]
Options:
-h Show help message
-s <speed> Set mobile robot speed. Default: 0.5
-c <count> Set repeat count. Default: 1

7. 잘못된 입력에 대한 주의
현재 코드는 간단한 예제이므로 다음과 같은 입력에는 예외가 발생할 수 있습니다.
ros2 run my_cpp_package patrol_node -s fast
fast는 숫자가 아니기 때문에 std::stod()에서 오류가 발생합니다.

조금 더 안전하게 작성하려면 다음처럼 예외 처리를 넣을 수 있습니다.
try {
speed = std::stod(speed_option);
} catch (const std::exception & e) {
fprintf(stderr, "Invalid speed value: %s\n", speed_option);
return 1;
}
강의 초반에는 기본 구조를 이해하는 것이 먼저입니다.

실제 프로젝트 코드에서는 이런 예외 처리를 넣는 편이 맞습니다.

'강좌 > ROS2' 카테고리의 다른 글
| 서비스 정의 만들기 (0) | 2026.05.21 |
|---|---|
| launch 파일에서 실행 인자 사용하기 #1 (0) | 2026.05.15 |
| ROS 2 C++ 파라미터 실습 (0) | 2026.05.15 |
| ROS 2 C++ Action Server / Client 실습 #2 (0) | 2026.05.15 |
| ROS 2 C++ 서비스 프로그래밍 이해하기 (0) | 2026.05.15 |