1261.26 토픽 통신의 QoS(Quality of Service) 정책
1. QoS 정책의 개념과 필요성
ROS2의 토픽 통신은 DDS(Data Distribution Service) 미들웨어를 기반으로 동작하며, QoS(Quality of Service) 정책은 이 통신의 동작 특성을 세밀하게 제어하는 설정 체계이다. QoS 정책은 발행자(Publisher)와 구독자(Subscriber) 각각에 독립적으로 적용되며, 메시지의 전달 보장 수준, 데이터의 지속성, 수신 큐의 관리 방식 등을 규정한다.
로봇 시스템에서는 센서 데이터의 실시간 스트리밍, 제어 명령의 신뢰성 있는 전달, 진단 정보의 주기적 발행 등 상이한 통신 요구사항이 공존한다. QoS 정책은 이러한 다양한 요구사항을 단일 통신 프레임워크 내에서 충족시키기 위한 핵심 메커니즘이다.
2. 주요 QoS 정책 항목
2.1 신뢰성(Reliability)
신뢰성 정책은 메시지 전달의 보장 수준을 결정하는 가장 기본적인 QoS 항목이다.
| 정책 값 | 동작 특성 |
|---|---|
RELIABLE | 메시지의 도착을 보장하며, 손실된 메시지에 대해 재전송을 수행한다. TCP와 유사한 전달 보장을 제공한다 |
BEST_EFFORT | 메시지 전달을 보장하지 않으며, 손실된 메시지에 대한 재전송을 수행하지 않는다. UDP와 유사한 동작 특성을 나타낸다 |
로봇 제어 명령이나 상태 전이 메시지처럼 데이터 손실이 시스템의 안전성에 직접적으로 영향을 미치는 경우에는 RELIABLE 정책을 적용하여야 한다. 반면, 고주파 센서 데이터 스트리밍에서는 지연 최소화가 우선시되므로 BEST_EFFORT 정책이 적합하다.
2.2 내구성(Durability)
내구성 정책은 구독자가 토픽에 합류하기 이전에 발행된 메시지의 수신 가능 여부를 결정한다.
| 정책 값 | 동작 특성 |
|---|---|
VOLATILE | 구독자가 연결된 이후에 발행되는 메시지만 수신한다. 과거 메시지는 전달되지 않는다 |
TRANSIENT_LOCAL | 발행자가 보유한 최근 메시지를 구독자 연결 시점에 즉시 전달한다. 늦은 합류(Late-Joining) 구독자에 대한 데이터 제공이 가능하다 |
로봇의 초기 구성 매개변수나 지도 데이터와 같이 구독 시점에 관계없이 최신 상태를 즉시 획득하여야 하는 경우, TRANSIENT_LOCAL 정책이 유용하다.
2.3 이력(History)
이력 정책은 발행자와 구독자의 내부 큐에서 메시지를 유지하는 방식을 규정한다.
| 정책 값 | 동작 특성 |
|---|---|
KEEP_LAST | 지정된 깊이(Depth) 값만큼의 최근 메시지만 유지하며, 큐가 가득 찬 경우 가장 오래된 메시지부터 폐기한다 |
KEEP_ALL | 수신된 모든 메시지를 유지하며, 시스템 자원이 허용하는 범위 내에서 큐를 확장한다 |
KEEP_LAST 정책의 깊이 값은 create_publisher() 또는 create_subscription() 호출 시 rclcpp::QoS 생성자의 인자로 전달된다. 일반적인 센서 데이터 토픽에서는 깊이 값으로 1에서 10 사이의 값을 설정하며, 비정상적으로 큰 값은 메모리 사용량의 급증을 유발할 수 있다.
2.4 수명(Lifespan)
수명 정책은 발행된 메시지가 유효한 시간 범위를 규정한다. 설정된 수명 기간이 경과한 메시지는 구독자에게 전달되지 않으며, 시스템에서 자동으로 폐기된다. 이 정책은 시간에 민감한 센서 데이터나 제어 명령에서 만료된 데이터의 처리를 방지하는 데 활용된다.
2.5 기한(Deadline)
기한 정책은 연속된 메시지 간의 최대 허용 시간 간격을 규정한다. 발행자 측에서는 지정된 기한 내에 메시지를 발행하여야 하며, 구독자 측에서는 지정된 기한 내에 메시지를 수신하여야 한다. 기한이 초과되면 DDS 미들웨어가 위반 이벤트를 감지하며, ROS2에서는 deadline_missed 이벤트를 통해 사용자에게 통지한다.
로봇 제어 루프에서 센서 데이터의 주기적 수신이 보장되어야 하는 경우, 기한 정책을 통해 데이터 공급의 중단을 조기에 감지할 수 있다.
2.6 지연 허용(Latency Budget)
지연 허용 정책은 메시지 전달에 허용되는 최대 지연 시간을 DDS 미들웨어에 통지한다. 이 값은 미들웨어의 전송 최적화에 활용되며, 엄격한 전달 보장이 아닌 최적화 힌트(Hint)로서 기능한다. 지연 허용 값이 작으면 미들웨어는 즉시 전송을 시도하고, 큰 값이면 배치(Batch) 전송 등의 최적화를 적용할 수 있다.
2.7 활성도(Liveliness)
활성도 정책은 발행자 엔티티의 생존 여부를 구독자가 감지할 수 있도록 하는 메커니즘이다.
| 정책 값 | 동작 특성 |
|---|---|
AUTOMATIC | DDS 미들웨어가 자동으로 활성도 신호를 전송하며, 참여자(Participant) 수준에서 생존이 확인된다 |
MANUAL_BY_TOPIC | 발행자가 명시적으로 활성도 신호를 전송하여야 하며, 개별 토픽 수준에서 생존이 확인된다 |
활성도 정책에는 임대 기간(Lease Duration)이 설정되며, 해당 기간 내에 활성도 신호가 수신되지 않으면 구독자는 발행자의 비활성 상태를 감지한다. 이는 로봇 시스템의 장애 검출(Fault Detection) 메커니즘에 직접 활용된다.
3. QoS 호환성 규칙
발행자와 구독자 간 통신이 성립하기 위해서는 양측의 QoS 정책이 상호 호환되어야 한다. DDS 명세는 QoS 호환성에 대해 RxO(Requested/Offered) 규칙을 정의하며, 이는 구독자가 요청하는(Requested) 서비스 수준이 발행자가 제안하는(Offered) 서비스 수준 이하이어야 함을 의미한다.
주요 QoS 항목별 호환성 규칙은 다음과 같다.
| QoS 항목 | 호환 조건 |
|---|---|
| 신뢰성 | 구독자 BEST_EFFORT ↔ 발행자 BEST_EFFORT 또는 RELIABLE. 구독자 RELIABLE ↔ 발행자 RELIABLE만 허용 |
| 내구성 | 구독자 VOLATILE ↔ 발행자 VOLATILE 또는 TRANSIENT_LOCAL. 구독자 TRANSIENT_LOCAL ↔ 발행자 TRANSIENT_LOCAL만 허용 |
| 기한 | 구독자의 기한 ≥ 발행자의 기한 |
| 활성도 임대 기간 | 구독자의 임대 기간 ≥ 발행자의 임대 기간 |
QoS 불일치가 발생하면 ROS2 런타임은 경고 메시지를 로그에 출력하며, 해당 발행자-구독자 쌍 간의 통신은 수립되지 않는다. ros2 doctor 명령이나 ros2 topic info -v 명령을 통해 QoS 불일치 여부를 진단할 수 있다.
4. ROS2 사전 정의 QoS 프로파일
ROS2는 빈번하게 사용되는 QoS 설정 조합을 사전 정의 프로파일(Predefined QoS Profile)로 제공한다.
| 프로파일 | 신뢰성 | 내구성 | 이력 | 깊이 | 주요 용도 |
|---|---|---|---|---|---|
rclcpp::SensorDataQoS | BEST_EFFORT | VOLATILE | KEEP_LAST | 5 | 고주파 센서 데이터 |
rclcpp::SystemDefaultsQoS | RELIABLE | VOLATILE | KEEP_LAST | 10 | 범용 통신 |
rclcpp::ServicesQoS | RELIABLE | VOLATILE | KEEP_LAST | 10 | 서비스 통신 내부 |
rclcpp::ParametersQoS | RELIABLE | VOLATILE | KEEP_LAST | 1000 | 매개변수 이벤트 |
이 프로파일들은 로봇 시스템에서의 전형적인 사용 패턴을 반영하여 설계되었으며, 개발자는 이를 기반으로 프로젝트의 요구사항에 맞게 개별 정책 값을 조정할 수 있다.
5. QoS 정책 설정의 실제 적용
5.1 센서 데이터 토픽의 QoS 설정
LiDAR, 카메라, IMU 등의 고주파 센서 데이터를 전달하는 토픽에서는 BEST_EFFORT 신뢰성과 VOLATILE 내구성을 조합하여 전송 지연을 최소화한다. 센서 데이터는 주기적으로 갱신되므로 개별 메시지의 손실보다 최신 데이터의 신속한 전달이 우선시된다.
auto qos = rclcpp::SensorDataQoS();
auto sub = this->create_subscription<sensor_msgs::msg::LaserScan>(
"scan", qos, callback);
5.2 제어 명령 토픽의 QoS 설정
속도 명령(cmd_vel)이나 관절 위치 명령처럼 제어 루프의 일부를 구성하는 토픽에서는 RELIABLE 신뢰성을 적용하되, 깊이를 1로 설정하여 항상 최신 명령만 유지하는 방식이 일반적이다.
5.3 상태 정보 토픽의 QoS 설정
로봇의 현재 상태, 지도 데이터, 좌표 변환 정보 등 늦은 합류 구독자에게도 즉시 제공되어야 하는 데이터의 경우, TRANSIENT_LOCAL 내구성과 RELIABLE 신뢰성을 결합하여 설정한다.
6. QoS 정책과 네트워크 환경의 상호작용
무선 네트워크 환경에서 동작하는 로봇 시스템에서는 패킷 손실률과 지연 변동(Jitter)이 유선 환경보다 현저히 높다. 이러한 환경에서 RELIABLE 정책을 적용하면 재전송으로 인한 추가 지연이 발생할 수 있으므로, 응용의 시간적 제약 조건을 고려하여 신뢰성 정책을 선택하여야 한다.
DDS 미들웨어의 전송 계층 설정(예: UDP 유니캐스트/멀티캐스트, 공유 메모리)도 QoS 정책의 실제 동작에 영향을 미친다. 동일 호스트 내의 노드 간 통신에서는 공유 메모리(Shared Memory) 전송을 활용하여 QoS 정책의 오버헤드를 최소화할 수 있다.
7. 참고 문헌
- OMG, “Data Distribution Service (DDS) Specification, Version 1.4,” Object Management Group, 2015.
- Open Robotics, “ROS 2 Documentation: About Quality of Service Settings,” https://docs.ros.org/en/humble/Concepts/About-Quality-of-Service-Settings.html, 2022.
- Pardo-Castellote, G., “OMG Data Distribution Service: Architectural Overview,” Proceedings of the 23rd International Conference on Distributed Computing Systems Workshops, 2003.
- Maruyama, Y., Kato, S., Azumi, T., “Exploring the Performance of ROS2,” Proceedings of the 13th International Conference on Embedded Software (EMSOFT), 2016.