대상: ROS(Melodic/Noetic) 환경에서 프로젝트 규모가 커졌을 때, launch 파일을 체계적으로 구성하고 관리하고 싶은 개발자
환경: Ubuntu 20.04 / ROS Noetic / catkin_make
1. 문제/주제 요약
처음에는 단일 bringup.launch 하나로도 충분하지만,
프로젝트가 커질수록 이런 문제가 생깁니다:
- launch 파일이 수백 줄이 되어 관리가 어려움
- 센서/로컬라이제이션/내비게이션 등이 서로 얽힘
- 일부 노드만 테스트하려고 해도 전체를 실행해야 함
→ 이런 문제를 해결하려면 launch 파일을 계층적으로 분리해야 합니다.
이 글에서는 실무에서 사용하는 launch 계층 구조 설계 패턴을 정리합니다.
2. 기본 원칙
ROS 프로젝트의 launch 파일은 다음 기준으로 나누면 가장 관리가 쉽습니다:
| 계층 | 역할 | 예시 파일 |
|---|---|---|
| 1단계: Bringup | 전체 시스템 실행 | bringup.launch |
| 2단계: 모듈 단위 | 센서, 로컬라이제이션, 내비게이션 등 | sensors.launch, localization.launch |
| 3단계: 하위 구성 요소 | 실제 노드 실행 | lidar.launch, camera.launch |
| 4단계: 테스트/디버깅 | 단일 기능 테스트용 | rviz_test.launch, camera_only.launch |
3. 디렉토리 구조 예시
my_robot_pkg/
├── launch/
│ ├── bringup.launch ← 전체 시스템 실행
│ ├── sensors/
│ │ ├── lidar.launch
│ │ ├── camera.launch
│ │ └── sensors.launch ← 센서 전체 포함
│ ├── localization/
│ │ └── localization.launch
│ ├── navigation/
│ │ └── navigation.launch
│ ├── visualization/
│ │ └── rviz.launch
│ └── tests/
│ └── camera_test.launch
└── config/
├── camera.yaml
├── lidar.yaml
├── amcl.yaml
└── move_base.yaml
이 구조는 실제 로봇 bring-up 및 유지보수 시 매우 유용합니다.
각 기능을 독립적으로 테스트할 수 있고, 상위 파일에서 쉽게 include 가능합니다.
4. 단계별 설계 예시
(1) 하위 단위 launch (노드 실행용)
launch/sensors/lidar.launch
<launch>
<arg name="port" default="/dev/ttyUSB0"/>
<arg name="baudrate" default="115200"/>
<node pkg="rplidar_ros" type="rplidarNode" name="lidar">
<param name="serial_port" value="$(arg port)"/>
<param name="serial_baudrate" value="$(arg baudrate)"/>
<param name="frame_id" value="laser_frame"/>
</node>
</launch>
launch/sensors/camera.launch
<launch>
<node pkg="usb_cam" type="usb_cam_node" name="camera">
<rosparam file="$(find my_robot_pkg)/config/camera.yaml" command="load" />
</node>
</launch>
(2) 중간 단위 launch (모듈 그룹화)
launch/sensors/sensors.launch
<launch>
<include file="$(find my_robot_pkg)/launch/sensors/lidar.launch" />
<include file="$(find my_robot_pkg)/launch/sensors/camera.launch" />
</launch>
launch/localization/localization.launch
<launch>
<node pkg="amcl" type="amcl" name="amcl" output="screen">
<rosparam file="$(find my_robot_pkg)/config/amcl.yaml" command="load"/>
</node>
</launch>
(3) 상위 Bringup (전체 실행용)
launch/bringup.launch
<launch>
<!-- 공통 파라미터 -->
<param name="use_sim_time" value="false"/>
<!-- 하위 모듈 포함 -->
<include file="$(find my_robot_pkg)/launch/sensors/sensors.launch" />
<include file="$(find my_robot_pkg)/launch/localization/localization.launch" />
<include file="$(find my_robot_pkg)/launch/navigation/navigation.launch" />
<include file="$(find my_robot_pkg)/launch/visualization/rviz.launch" />
<!-- Launch 인자 (옵션) -->
<arg name="use_rviz" default="true"/>
<node pkg="rviz" type="rviz" name="rviz" if="$(arg use_rviz)"
args="-d $(find my_robot_pkg)/rviz/nav.rviz"/>
</launch>
👉 실행 명령:
roslaunch my_robot_pkg bringup.launch
5. 테스트/디버깅 전용 launch
launch/tests/camera_test.launch
<launch>
<include file="$(find my_robot_pkg)/launch/sensors/camera.launch" />
<node pkg="image_view" type="image_view" name="camera_viewer"/>
</launch>
이런 식으로 기능별 테스트용 launch 파일을 만들어두면,
전체 시스템을 실행하지 않아도 특정 센서나 노드만 검증할 수 있습니다.
6. 환경별 분리 (Simulation vs Real)
현장에서는 “실제 로봇용”과 “시뮬레이터용” 구성이 다르기 때문에
다음처럼 환경별로 나누는 것이 좋습니다.
launch/
├── bringup_real.launch
└── bringup_sim.launch
bringup_sim.launch
<launch>
<arg name="world" default="office.world"/>
<include file="$(find my_robot_gazebo)/launch/gazebo.launch">
<arg name="world_name" value="$(arg world)"/>
</include>
<include file="$(find my_robot_pkg)/launch/bringup.launch"/>
</launch>
→ 시뮬레이션에서는 Gazebo 노드가 포함되고,
실제 하드웨어에서는 bringup_real.launch 만 실행하도록 구분합니다.
7. 고급 패턴: 선택적 모듈 실행 (arg + if)
Bring-up 시 특정 모듈만 실행하고 싶을 때:
<launch>
<arg name="use_lidar" default="true"/>
<arg name="use_camera" default="false"/>
<include file="$(find my_robot_pkg)/launch/sensors/lidar.launch" if="$(arg use_lidar)" />
<include file="$(find my_robot_pkg)/launch/sensors/camera.launch" if="$(arg use_camera)" />
</launch>
👉 실행 시 옵션 지정:
roslaunch my_robot_pkg bringup.launch use_camera:=true
8. 추가 팁 / 자주 하는 실수
- ⚠️ launch 파일이 깊어질수록
$(find ...)경로 관리가 중요
→ 패키지 이름 오타 하나로include실패 - ⚠️ 파라미터(YAML)와 launch 파일을 같은 폴더에 넣지 말기
→config/폴더에 따로 정리해야 유지보수 용이 - ✅ 상위 launch에서는 직접 노드 실행을 최소화하고,
대부분을 하위 파일에서include형태로 관리 - ✅ 네임스페이스 구조를 일관성 있게 유지 (
/robot1/lidar,/robot1/camera등)
9. 정리
| 계층 | 파일 예시 | 역할 |
|---|---|---|
| Bring-up | bringup.launch | 전체 시스템 실행 |
| 모듈 단위 | sensors.launch, navigation.launch | 기능 그룹별 묶음 |
| 하위 노드 | lidar.launch, camera.launch | 개별 노드 실행 |
| 테스트용 | camera_test.launch | 단위 기능 검증 |
| 환경별 | bringup_sim.launch, bringup_real.launch | 시뮬/실기 구분 |
👉 정리하면,
“각 기능별로 독립 실행 가능 + 상위 파일에서 조립 가능”한 구조를 만드는 것이 핵심입니다.
이렇게 하면 시스템이 커져도 launch 파일이 깨끗하게 유지됩니다.