ROS 1과 대두되는 가장 큰 차이점으로, ROS 2는 DDS를 미들웨어로 기반하여 개편되었습니다. 따라서 DDS에 대한 개요와 기능을 이해하는 것은 ROS 2의 성질을 파악하는 데 많은 도움이 됩니다.
DDS - Data Distribution Service는 OMG에서 정의한 Publish-Subscribe 방식의 실시간 데이터 분배 서비스 표준입니다.
Pub-Sub이라는 용어는 ROS 개발자에게 무척 익숙한 단어이지요? DDS의 기본 통신 개념은 ROS의 Topic과 매우 유사합니다. 이러한 결론을 머리속에 잘 담아두고 계속해서 진행해 보겠습니다.
OMG(Object Management Group)는 분산 객체 컴퓨팅(Distributed Object Computing) 영역의 표준을 제정하는 국제 비영리 컨소시엄으로 영향력 있는 각종 세계 표준을 정의하고 있습니다.
OMG DDS는 통신 프로토콜이 아닌 기능적 표준으로, 위 그림과 같이 TCP/UDP 같은 통신 프로토콜 위에서 정의되는 객체입니다.
그림의 아래에서부터 OMG DDS의 구조를 간단히 살펴보겠습니다.
RTPS Layer는 네트워크 내, 참여자 정보를 유지하고, 네트워크 참여자에 대한 정보를 기반으로 자동 검색을 해주며, (같은 네트워크를 사용하는 ROS 2 시스템은 서로 통신이 가능합니다.) 더불어, 참여자의 동적 추가와 이탈에 대응하는 기능을 합니다.
RTPS는 OMG에 의해 표준화된, 데이터 분산 시스템을 위한 프로토콜로써 Pub-Sub 구조의 통신 모델을 지원합니다. UDP와 같이 신뢰성 없는 계층 위에서도 동작 가능하도록 설계되었으며, 4가지 모듈로 구성되어 있습니다.
ROS 2를 사용하는 두 디바이스는 같은 네트워크를 사용하고 있다면 자동으로 서로를 인식할 수 있습니다. 어떻게 이러한 동작이 가능하며, 이를 위한 필요조건은 무엇인지 살펴보겠습니다.
Discovery를 위해 필요한 정보들 - DDS 미들웨어 통신을 위해 아래 4가지 정보를 사전에 교환해야 합니다.
DDS RTPS도 결국 UDP나 TCP 네트워크 레이어를 사용하며, 이를 위해서 실질적으로 IP와 PORT등의 정보가 필요합니다. 하지만, DDS는 사용자가 주소를 지정하지 않아도 “Topic”만으로 통신이 가능합니다. 이를 가능하게 해주는 것이 Locator이며, 이는 Middle Ware단에서 능동적으로 통신에 필요한 정보를 포함하는 새로운 개념을 별도로 생성하는 것입니다.
DDS 표준에서는 Discovery를 수행하는 절차를 PDP 와 EDP로 구분하고 있습니다.
vendor에 따라 다양한 PDP와 EDP를 지원할 수 있지만, 호환성을 위해 모든 RTPS는 SPDP(Simple Participant Discovery Protocol)와 SEDP(Simple Endpoint Discovery Protocol)를 필수로 지원해야합니다. 서로 다른 vendor를 가진 머신 사이에 통신이 가능한 이유이기도 합니다.
그림을 통해 SPDP와 SEDP를 활용한 Discovery 절차에 대해 알아봅시다.
Discovery 과정을 한번에 정리한 그림입니다. 다시 한 번 의미를 이해하면서 과정을 복기해봅시다.
DCPS Layer는 RTPS Layer와 Application 사이의 인터페이스 역할을 합니다. 이후 다뤄지는 Participant, Domain, Topic 등을 정의하고, Publish-Subscribe를 수행합니다. 더불어, DDS의 중요한 기능 중 하나인 QoS(Quality of Service)도 담당하고 있습니다.
구현 측면에서, DCPS는 Data read/write API를 제공함으로 응용 프로그램들 사이 데이터를 교환할 상대에 대한 인지 없이 원하는 데이터의 송수신이 가능하게 합니다.
DataWriter는 송신자, DataReader는 수신자의 역할을 합니다. DataWriter는 Sample(실제 데이터)을 생성하고 전송하는 역할을 하며, DataReader는 Sample을 수신하는 기능을 합니다. 단일 DataWriter와 DataReader는 단일 Topic만을 보유할 수 있습니다.
데이터 Publish를 담당하는 객체로, 하나의 Publisher는 다수의 DataWriter를 가질 수 있습니다. 때문에, 각 Publisher들은 여러 Topic 데이터를 Publish 할 수 있습니다. Publish하고자 하는 데이터 객체의 값이 Publisher에게 전해지면 Publisher는 자신에게 설정된 QoS값에 따라 연관된 Subscriber에게 전달합니다.
데이터 Subscribe를 담당하는 객체로, Publisher와 유사하게 다수의 DataReader를 가질 수 있으며 여러 Topic 데이터를 수신할 수 있습니다. Subscriber가 데이터를 수신한 이후, 응용 프로그램은 DataReader를 통해 실제 데이터로 접근하는 방식입니다.
Topic
Topic은 Publish-Subscribe의 관계를 정의하는 Key입니다. topic은 데이터 타입과 해당 데이터의 QoS에 대한 정보를 담고 있습니다. QoS를 Topic 데이터에 추가하고, Topic과 연관된 DataWriter, Datawriter에 연관된 QoS를 설정하는 식으로 제어됩니다. (Subscriber 측도 동일합니다.)
Topic의 이름은 Domain 내에서 유일해야 합니다.
Participant
Participant는 DDS Publisher와 Subscriber를 담게 되는 객체입니다. ROS 2의 Node안에 다수의 Publisher와 Subscriber와 공존할 수 있는 것처럼, Participant도 다수의 DataWriter와 DataReader를 가질 수 있습니다.
Domain
Domain은 Participant들이 활동하는 영역으로, 같은 Domain을 갖는 Participant내에서만 정보전달을 할 수 있습니다. ROS 2 터미널의 실행 시 ROS_DOMAIN_ID라는 콘솔 출력이 나왔던 것을 기억하시나요?
*************** Startup Menu for ROS ***************
* Usage: To set ROS env to be auto-loaded, please *
* assign ros_option in ros_menu/config.yaml *
******************************************************
0) Do nothing
1) ROS 1 noetic
2) ROS 2 foxy
3) ROS2/ROS1_bridge
Please choose an option: 2
------------------------------------------------------
* ROS_DOMAIN_ID = 30
------------------------------------------------------
이렇게 DDS의 통신 구조에 대해서 알아보았습니다. 위 구조에서 실제 사용자는 Topic, Publisher, Subscriber만 구현하면 되며, DataWriter, DataReader와 RTPS, DCPS는 DDS가 알아서 처리하게 됩니다. 이러한 DDS의 장점에 기반하여 ROS 2 시스템이 올라가게 되는 것이지요.
TCPROS/UDPROS라는 자체 프로토콜을 사용했던 기존 ROS 1과는 달리, ROS 2에서는 QoS 옵션을 통해 원하는 기능을 선택적으로 사용할 수 있습니다. 이는 DDS의 QoS를 도입하였기 때문으로, Publisher, Subscriber를 선언할 때, QoS를 매개변수형태로 지정하는 방식이 사용됩니다.
상황에 따라 데이터의 신뢰성이 중요할 수도 있고, 버퍼의 크기를 크게 하여 Topic의 안정성을 높여야 할 수도 있습니다. 이러한 통신의 품질을 옵션화하기 위해서, DDS에서는 아래와 같은 22가지의 QoS를 정의하고 있습니다.
각각의 QoS 옵션은 연관된 조합으로 Topic, DataWriter, DataReader, Publisher, Subscriber, Domain, Participant에 적용되며, 본 세션에서는 주로 사용되는 QoS를 위주로 살펴보고자 합니다.
알파벳은 다음과 같은 의미를 갖습니다. T : TOPIC, DR : DataReader, DW : DataWriter, P : Publisher, S : Subscriber
RxO는 Requested/Offered의 약자로 QoS가 적용되는 대상을 Publisher(발간/송신) 측과 Subscriber(구독/수신) 측으로 구분해서 서로의 상관관계를 표현하는 방법입니다.
Changeable이 ‘YES’ 일 경우에는, 동작하면서도 QoS 의 값이 변경될 수 있지만, ‘NO’일 경우에는 처음 생성된 이후에는 변경할 수 없습니다.
Partition과 Domain의 차이 - 다른 Domain들에 속하는 개체들은 완전히 서로 독립 된 상태입니다. Entity는 다수의 Partition에 있을 수 있지만 하나의 Domain에만 속할 수 있습니다.
ROS 2에서는 자주 사용되는 QoS 조합을 묶어 RMW QoS Profile이라는 이름으로 제공하고 있습니다. 지금까지 우리가 queue_size만을 전달하고 있었지만, 사실은 아래 사진의 Default에서 Depth만 바꿔주고 있었던 것입니다.
ros2에서 QoS 설정하는 방법은 매우 간단합니다. Publisher, Subscriber 클래스를 생성하면서 QoS 옵션을 매개변수로 전달하면 됩니다.
from rclpy.qos import qos_profile_sensor_data
self.string_publisher = self.create_publisher(String, 'qos_test_topic', qos_profile_sensor_data)
from rclpy.qos import QoSDurabilityPolicy
from rclpy.qos import QoSHistoryPolicy
from rclpy.qos import QoSProfile
from rclpy.qos import QoSReliabilityPolicy
my_profile = QoSProfile(
reliability=QoSReliabilityPolicy.BEST_EFFORT,
history=QoSHistoryPolicy.KEEP_LAST,
depth=10,
durability=QoSDurabilityPolicy.VOLATILE
)
self.string_publisher = self.create_publisher(String, 'qos_test_topic', my_profile)
=> 참고 링크 : rclpy/qos.py
# Terminal 1 - publisher
$ ros2 run py_topic_tutorial qos_example_publisher
# Terminal 2 - subscriber
$ ros2 run py_topic_tutorial qos_example_subscriber
# Terminal 3 - topic info
$ ros2 topic info /qos_test_topic --verbose
Type: std_msgs/msg/String
Publisher count: 1
Node name: twist_pub_node
Node namespace: /
Topic type: std_msgs/msg/String
Endpoint type: PUBLISHER
GID: 60.77.10.01.f3.67.78.3d.6b.0c.cc.7b.00.00.14.03.00.00.00.00.00.00.00.00
QoS profile:
Reliability: RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT
Durability: RMW_QOS_POLICY_DURABILITY_VOLATILE
Lifespan: 9223372036854775807 nanoseconds
Deadline: 9223372036854775807 nanoseconds
Liveliness: RMW_QOS_POLICY_LIVELINESS_AUTOMATIC
Liveliness lease duration: 9223372036854775807 nanoseconds
Subscription count: 1
Node name: string_sub_node
Node namespace: /
Topic type: std_msgs/msg/String
Endpoint type: SUBSCRIPTION
GID: d2.03.10.01.d5.6b.69.e0.be.3f.b5.a2.00.00.14.04.00.00.00.00.00.00.00.00
QoS profile:
Reliability: RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT
Durability: RMW_QOS_POLICY_DURABILITY_VOLATILE
Lifespan: 9223372036854775807 nanoseconds
Deadline: 9223372036854775807 nanoseconds
Liveliness: RMW_QOS_POLICY_LIVELINESS_AUTOMATIC
Liveliness lease duration: 9223372036854775807 nanoseconds
DDS QoS는 RxO - requested by offered 특성을 갖고 있어 서로 양립할 수 없는 조합이 존재합니다. 예를 들어, Publish의 Reliability가 BEST_EFFORT일때, Subscriber의 Reliability가 RELIABLE라면, Topic 통신이 발생할 수 없습니다.
my_profile = QoSProfile(
reliability=QoSReliabilityPolicy.BEST_EFFORT,
history=QoSHistoryPolicy.KEEP_LAST,
depth=10,
durability=QoSDurabilityPolicy.VOLATILE
)
...
self.string_publisher = self.create_publisher(String, 'qos_test_topic', qos_profile_sensor_data)
my_profile = QoSProfile(
reliability=QoSReliabilityPolicy.RELIABLE,
history=QoSHistoryPolicy.KEEP_LAST,
depth=10,
durability=QoSDurabilityPolicy.VOLATILE
)
...
self.pose_subscriber = self.create_subscription(
String, 'qos_test_topic', self.sub_callback, my_profile
)
$ ros2 run py_topic_tutorial qos_example_publisher
[WARN] [1673945160.449603592] [twist_pub_node]: New subscription discovered on this topic, requesting incompatible QoS. No messages will be sent to it. Last incompatible policy: RELIABILITY_QOS_POLICY
$ ros2 run py_topic_tutorial qos_example_subscriber
[WARN] [1673945160.455319911] [string_sub_node]: New publisher discovered on this topic, offering incompatible QoS. No messages will be received from it. Last incompatible policy: RELIABILITY_QOS_POLICY
QoS를 통해 원하는 도메인에서의 성능을 끌어올리고 안정성을 갖춘 시스템을 구축합시다.
⇒ 다음 페이지에서 계속됩니다.