학습 내용
과제 설명
< 도착하는 데이터를 미처 처리하지 못하면 어떻게 되는가? >
노드 1(Sender)에서 노드 2(Receiver)로 구독자의 콜백함수 내에 시간이 많이 걸리는 코드를 넣고 대량으로 전송하여 노드 2의 토픽 처리가 지연되는 상황을 만들어본다. 우선 C++ 파일 2개(sender_overflow.cpp, receiver_overflow.cpp)와 launch 파일 1개(sr_overflow.launch)를 만든다. 우선 1초에 1000번씩 숫자를 1씩 증가해서 토픽을 발행한다. 다음으로 Receiver의 콜백함수 안에 시간이 많이 걸리는 코드를 넣어서 의도적으로 토픽 처리에서 지연이 발생하도록 한다. 이후 화면에 토픽을 출력하여 토픽의 누락 여부에 대해 대해 확인해 보자. 또한 이러한 사실을 발행자가 알고 있는 지나 알려줄 수 있는지에 대해서도 알아보자.
과제 수행
먼저 과제를 위해 필요한 파일들을 생성한다. 생성 위치는 다음과 같다.
파일 생성 위치
xycar_ws
├─ build
├─ devel
└─ src
├─ CMakeLists.txt
└─ msg_send
├─ CMakeLists.txt
├─ launch
│ └─ sr_overflow.launch (new!)
└─ src
├─ sender_overflow.cpp (new!)
└─ receiver_overflow.cpp (new!)
동작을 위한 소스 코드는 다음과 같다. 소스 코드는 C++로 작성하였다.
sender_overflow.cpp
#include <ros/ros.h>
#include <std_msgs/Int32.h>
int main(int argc, char **argv) {
ros::init(argc, argv, "sender_overflow");
ros::NodeHandle nh;
ros::Publisher pub = nh.advertise<std_msgs::Int32>("my_topic", 1);
ros::Rate rate(1000);
int count = 1;
while (pub.getNumSubscribers() == 0)
continue;
while (ros::ok()) {
std_msgs::Int32 msg;
msg.data = count;
pub.publish(msg);
count++;
rate.sleep();
}
return 0;
}
receiver_overflow.cpp
#include <ros/ros.h>
#include <std_msgs/Int32.h>
void callback(const std_msgs::Int32::ConstPtr& msg) {
ROS_INFO("callback is being processed");
ros::Duration(2.0).sleep(); // 5초 동안 sleep
ROS_INFO("%d", msg->data);
}
int main(int argc, char **argv) {
ros::init(argc, argv, "receiver_overflow");
ros::NodeHandle nh;
ros::Subscriber sub = nh.subscribe("my_topic", 1, callback);
ros::spin();
return 0;
}
sr_overflow.launch
<launch>
<node pkg="msg_send" type="sender_overflow" name="sender_overflow_node">
</node>
<node pkg="msg_send" type="receiver_overflow" name="receiver_overflow_node" output="screen">
</node>
</launch>
+) 앞선 예제와 마찬가지로 msg_send의 CMakeLists.txt에 조건들을 추가해줘야 한다.
https://leevision.tistory.com/80
[ROS 튜토리얼] ROS 노드 통신 프로그래밍
학습 내용 메시지를 통한 노드 간 통신 Teacher(Publisher)가 "my_topic"이라는 토픽을 Student(Subscriber)에게 전송하면 Student가 이 화면에 출력하는 토픽 통신 시스템을 구현해 보자. 언어는 C++를 사용한다.
leevision.tistory.com
먼저 receiver의 queue size를 10000으로 설정하고 출력을 확인해 보자. 이때는 버퍼 사이즈가 충분히 크기 때문에 토픽을 잃지 않고 콜백을 수행할 것이라 예상할 수 있다. 아래의 출력 결과에서 차례대로 숫자를 출력하는 것을 확인할 수 있다.
이번에는 receiver의 queue size를 1로 설정하고 어떤 변화가 있는지 확인해 보자. 아래의 출력 결과에서도 확인할 수 있듯이 받은 토픽이 1씩 증가하지 않는 것을 확인할 수 있다. 이를 통해 노드 통신 중 처리 지연이 발생할 경우 중간에서 토픽을 잃어버린다는 것을 알 수 있다.
결론
이번 실습은 노드 통신 중 처리 지연이 발생한 경우 데이터가 어떻게 되는 가에 대해 알아보았다. sender와 receiver에서 지연이 발생하게끔 코드를 작성하고 출력을 확인한 결과 버퍼 사이즈가 충분하지 않아 처리를 기다릴 수 없을 때 중간에서 토픽을 잃어버리는 것을 확인할 수 있었다. 이를 통해 실제 시스템을 구축하며 데이터의 유실이 발생하지 않도록 버퍼 사이즈 조정과 최적화가 필요하다는 것을 알 수 있었다.
'Study > ROS' 카테고리의 다른 글
[ROS 튜토리얼] 과제 #5. 협업해야 하는 노드를 순서대로 기동 시킬 수 있는가? (1) | 2023.10.04 |
---|---|
[ROS 튜토리얼] 과제 #4. 주기적 발송에서 타임슬롯을 오버하면 어떻게 되는가? (0) | 2023.10.04 |
[ROS 튜토리얼] 과제 #2. 데이터 크기에 따른 전송속도는 어떻게 되는가? (1) | 2023.10.03 |
[ROS 튜토리얼] 과제 #1. 누락 없이 모두 잘 도착하는가? (0) | 2023.10.03 |
[ROS 튜토리얼] ROS 통신 중 발생하는 다양한 문제 상황과 해결 방법 (1) | 2023.10.03 |