🎯 이 챕터의 목표
Ch.02에서 파라미터를 "노드의 설정값"이라 배웠고, Ch.03에서 ros2 param set으로 거북이 배경색을 바꿔봤어요.
이번엔 진짜 — 내가 만든 노드에 파라미터를 박고, YAML 파일로 관리하고, launch로 주입하는 방법까지.
이걸 익히면 코드를 안 고치고도 노드의 동작을 자유자재로 바꿀 수 있어요. 진짜 ROS2다워지는 순간이에요.
🤔 왜 파라미터를 쓰나?
Ch.04의 chatter_pub을 다시 보면 발행 주기가 1.0초로 하드코딩되어 있어요.
self.timer = self.create_timer(1.0, self.tick)
# ↑ 이게 하드코딩
이걸 0.5초로 바꾸려면? 코드 수정 → colcon build → 재실행. 매번 이러면 답답하죠.
파라미터로 빼두면:
- 코드 수정 없이 launch 파일 한 줄 바꾸면 끝
- 실행 중에도
ros2 param set으로 즉시 변경 가능 - 같은 노드를 다른 설정으로 여러 번 띄울 수 있음 (Ch.06 거북이 2마리처럼)
- YAML 파일로 환경별 설정 관리 (개발/스테이징/프로덕션)
· 노드 = 게임 본체
· 파라미터 = 화면 밝기, 마우스 감도, 사운드 볼륨 같은 옵션 다이얼
· YAML 파일 = "내 게임 프리셋" 저장 파일
🛠 STEP 1 — 노드에 파라미터 박기
chatter_pub.py를 수정해서 발행 주기와 메시지 접두어를 파라미터로 빼봐요.
cd ~/ros2_ws/src/my_first_pkg/my_first_pkg
nano chatter_pub.py
import rclpy
from rclpy.node import Node
from std_msgs.msg import String
class ChatterPub(Node):
def __init__(self):
super().__init__('chatter_pub')
# 🌟 파라미터 선언 (기본값 포함)
self.declare_parameter('publish_rate', 1.0)
self.declare_parameter('greeting', 'Hello ROS2')
# 🌟 파라미터 값 읽기
rate = self.get_parameter('publish_rate').value
self.greeting = self.get_parameter('greeting').value
self.pub = self.create_publisher(String, '/chatter', 10)
self.timer = self.create_timer(rate, self.tick)
self.count = 0
self.get_logger().info(
f'시작! rate={rate}s, greeting="{self.greeting}"'
)
def tick(self):
msg = String()
msg.data = f'{self.greeting} {self.count}'
self.pub.publish(msg)
self.get_logger().info(f'발행: "{msg.data}"')
self.count += 1
def main(args=None):
rclpy.init(args=args)
rclpy.spin(ChatterPub())
rclpy.shutdown()
if __name__ == '__main__':
main()
핵심 두 줄
self.declare_parameter('이름', 기본값)— 파라미터 선언. 반드시 declare 후 get!self.get_parameter('이름').value— 현재 값 가져오기
🔨 STEP 2 — 빌드 후 기본값으로 실행
cd ~/ros2_ws
colcon build --packages-select my_first_pkg
source ~/ros2_ws/install/setup.bash
ros2 run my_first_pkg chatter_pub
[INFO] [chatter_pub]: 시작! rate=1.0s, greeting="Hello ROS2"
[INFO] [chatter_pub]: 발행: "Hello ROS2 0"
[INFO] [chatter_pub]: 발행: "Hello ROS2 1"
...
아직은 그대로. 이제 파라미터를 바꿔보자.
🎚 STEP 3 — 실행 시 파라미터 주입 (4가지 방법)
방법 1 — 커맨드라인 (--ros-args -p)
ros2 run my_first_pkg chatter_pub \
--ros-args -p publish_rate:=0.3 -p greeting:="안녕 ROS2"
[INFO] [chatter_pub]: 시작! rate=0.3s, greeting="안녕 ROS2"
[INFO] [chatter_pub]: 발행: "안녕 ROS2 0"
[INFO] [chatter_pub]: 발행: "안녕 ROS2 1"
...
가장 간단한 방법. 한두 개 파라미터면 이걸로 충분.
방법 2 — 실행 중에 바꾸기 (ros2 param set)
# 노드가 돌아가는 상태에서, 다른 터미널
ros2 param list /chatter_pub
ros2 param get /chatter_pub publish_rate
ros2 param set /chatter_pub greeting "Bonjour"
__init__에서 한 번만 읽어서 timer에 박았기 때문에, set으로 바꿔도 즉시 반영 안 됨.
실시간 반영하려면 callback을 등록해야 해요 (이건 잠시 후).
방법 3 — YAML 파일
# chatter_config.yaml
chatter_pub:
ros__parameters:
publish_rate: 0.5
greeting: "Hola ROS2"
형식: <노드이름>: 아래 ros__parameters: 키, 그 아래 파라미터들. 들여쓰기 정확히.
ros2 run my_first_pkg chatter_pub \
--ros-args --params-file chatter_config.yaml
방법 4 — launch에서 주입 (가장 흔함)
from launch import LaunchDescription
from launch_ros.actions import Node
def generate_launch_description():
return LaunchDescription([
Node(
package='my_first_pkg',
executable='chatter_pub',
name='chatter_pub',
parameters=[{
'publish_rate': 0.5,
'greeting': '여기서 주입',
}],
output='screen',
),
])
실전에선 이게 거의 표준이에요. launch 파일이 노드 설정도 같이 관리.
📄 STEP 4 — YAML 파일을 패키지에 포함
YAML 파일을 패키지에 넣어서 launch가 자동으로 찾도록 만들어요.
cd ~/ros2_ws/src/my_first_pkg
mkdir config
nano config/chatter_params.yaml
chatter_pub:
ros__parameters:
publish_rate: 0.5
greeting: "환영합니다"
setup.py에 config 폴더 등록
import os
from glob import glob
from setuptools import setup
package_name = 'my_first_pkg'
setup(
name=package_name,
# ... 생략 ...
data_files=[
('share/ament_index/resource_index/packages',
['resource/' + package_name]),
('share/' + package_name, ['package.xml']),
(os.path.join('share', package_name, 'launch'),
glob('launch/*.launch.py')),
# 🌟 config 폴더 등록
(os.path.join('share', package_name, 'config'),
glob('config/*.yaml')),
],
# ...
)
launch 파일에서 YAML 경로로 사용
nano launch/chatter_with_params.launch.py
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch_ros.actions import Node
def generate_launch_description():
# 패키지 share 폴더에서 YAML 경로 자동으로 찾기
config = os.path.join(
get_package_share_directory('my_first_pkg'),
'config',
'chatter_params.yaml',
)
return LaunchDescription([
Node(
package='my_first_pkg',
executable='chatter_pub',
name='chatter_pub',
parameters=[config], # 🌟 YAML 경로 그대로 전달
output='screen',
),
])
get_package_share_directory가 핵심. 패키지가 어디 설치됐든 그 안의 config 파일을 정확히 찾아줘요.
상대경로 하드코딩 X.
빌드 & 실행
cd ~/ros2_ws
colcon build --packages-select my_first_pkg
source ~/ros2_ws/install/setup.bash
ros2 launch my_first_pkg chatter_with_params.launch.py
[INFO] [chatter_pub]: 시작! rate=0.5s, greeting="환영합니다"
[INFO] [chatter_pub]: 발행: "환영합니다 0"
...
🔄 실시간 파라미터 변경 — callback 등록
실행 중에 ros2 param set으로 값을 바꿨을 때 즉시 반영되도록 만들려면, 파라미터 변경 callback을 등록해야 해요.
import rclpy
from rclpy.node import Node
from rcl_interfaces.msg import SetParametersResult
from std_msgs.msg import String
class ChatterPubLive(Node):
def __init__(self):
super().__init__('chatter_pub_live')
self.declare_parameter('publish_rate', 1.0)
self.declare_parameter('greeting', 'Hello')
rate = self.get_parameter('publish_rate').value
self.greeting = self.get_parameter('greeting').value
self.pub = self.create_publisher(String, '/chatter', 10)
self.timer = self.create_timer(rate, self.tick)
self.count = 0
# 🌟 파라미터 변경 callback 등록
self.add_on_set_parameters_callback(self.on_param_change)
def on_param_change(self, params):
for p in params:
if p.name == 'greeting':
self.greeting = p.value
self.get_logger().info(f'greeting 변경: "{self.greeting}"')
elif p.name == 'publish_rate':
# timer 재생성
self.destroy_timer(self.timer)
self.timer = self.create_timer(p.value, self.tick)
self.get_logger().info(f'rate 변경: {p.value}s')
return SetParametersResult(successful=True)
def tick(self):
msg = String()
msg.data = f'{self.greeting} {self.count}'
self.pub.publish(msg)
self.count += 1
def main(args=None):
rclpy.init(args=args)
rclpy.spin(ChatterPubLive())
rclpy.shutdown()
if __name__ == '__main__':
main()
이제 진짜 실시간 반영:
# 노드 띄워두고
ros2 run my_first_pkg chatter_pub_live
# 다른 터미널
ros2 param set /chatter_pub_live greeting "한국어"
ros2 param set /chatter_pub_live publish_rate 0.1
출력하는 메시지가 즉시 한국어로 바뀌고 발행 속도도 빨라져요.
📦 YAML 파일 — 여러 노드 한꺼번에
실제 로봇 시스템은 노드가 10개 넘으니, YAML 한 파일에 여러 노드 설정을 모아둬요.
# config/robot.yaml
chatter_pub:
ros__parameters:
publish_rate: 0.5
greeting: "Robot says"
chatter_sub:
ros__parameters:
log_level: "info"
temperature_pub:
ros__parameters:
sensor_id: "living_room_01"
publish_rate: 2.0
units: "celsius"
valid_range: [10.0, 50.0]
launch에서 한 파일로 모두 주입 가능:
Node(
package='my_first_pkg',
executable='chatter_pub',
name='chatter_pub', # ← YAML의 노드 이름과 일치해야 함!
parameters=[config_path],
),
Node(
package='my_first_pkg',
executable='temperature_pub',
name='temperature_pub',
parameters=[config_path], # 같은 YAML 재사용
),
name=이 YAML의 키와 정확히 일치해야 파라미터가 매칭돼요. 대소문자/언더스코어 주의.
🌐 와일드카드 — 모든 노드 공통 설정
특정 파라미터를 모든 노드에 똑같이 주고 싶을 때:
# 모든 노드에 use_sim_time=true 적용
/**:
ros__parameters:
use_sim_time: true
# 특정 노드는 따로 오버라이드
chatter_pub:
ros__parameters:
publish_rate: 0.5
greeting: "Hi"
/**는 와일드카드. 시뮬레이션 환경(Gazebo)에서 모든 노드가 시뮬레이션 시간을 쓰게 할 때 자주 사용.
true면 노드가 /clock 토픽의 시간을 따라감.
Gazebo가 발행해줘요. 실시간이 아닌 빠른 재생/느린 재생 디버깅에 유용.
📜 파라미터 명령어 치트시트
# 노드의 파라미터 목록
ros2 param list /노드이름
# 값 보기
ros2 param get /노드이름 파라미터이름
# 값 설정
ros2 param set /노드이름 파라미터이름 값
# 모든 파라미터를 YAML로 덤프 (백업용)
ros2 param dump /노드이름 > backup.yaml
# 노드 실행 시 파라미터 주입
ros2 run 패키지 실행파일 --ros-args -p 파라미터:=값
ros2 run 패키지 실행파일 --ros-args --params-file config.yaml
# 노드 설명까지 보기
ros2 param describe /노드이름 파라미터이름
노드에서 파라미터를 쓰기 전 반드시 호출해야 하는 메서드는?
YAML 파라미터 파일에서 노드 이름 아래에 반드시 와야 하는 키는?
launch에서 같은 YAML 파일을 여러 노드가 공유할 때, 파라미터가 올바르게 매칭되려면 무엇이 일치해야 하나요?
실행 중인 노드에서 파라미터 변경을 즉시 반영하려면?
🎁 정리
- 파라미터 = 노드의 설정값 (코드 안 고치고 동작 바꾸기)
- 노드 안에서:
declare_parameter('이름', 기본값)→get_parameter('이름').value - 주입 4가지: 커맨드라인(
-p) /ros2 param set/ YAML / launchparameters= - YAML 구조:
노드이름 → ros__parameters → 키:값 - 패키지에 config 폴더 +
setup.py의data_files에 등록 - launch에서
get_package_share_directory로 YAML 경로 자동 검색 - 실시간 반영은
add_on_set_parameters_callback으로 /**와일드카드로 모든 노드 공통 설정 (대표 예:use_sim_time)
여기까지 오면 ROS2의 소프트웨어 측면은 거의 다 본 거예요. 다음은 로봇의 모양을 표현하는 URDF로 넘어갑니다. 🦾