학습 내용
과제 설명
< 데이터 크기에 따른 전송속도는 어떻게 되는가? >
노드 1(Sender)에서 노드 2(Receiver)로 정해진 크기의 데이터를 반복해서 대량으로 보낸 뒤 송수신 속도를 체크해 본다. 우선 C++ 파일 2개(sender_speed.cpp, receiver_speed.cpp)와 launch 파일 1개(sr_speed.launch)를 만든다. 이후 노드 1에서 노드 2로 1M, 5M, 10M, 20M, 50M 크기의 데이터를 전송한 뒤 평균 전송속도와 전송시간을 확인하고 비교해 본다. 전송되는 데이터의 크기에 따라 어떻게 변하는지 확인한다.
과제 수행
먼저 과제를 위해 필요한 파일들을 생성한다. 생성 위치는 다음과 같다.
파일 생성 위치
xycar_ws
├─ build
├─ devel
└─ src
├─ CMakeLists.txt
└─ msg_send
├─ CMakeLists.txt
├─ launch
│ └─ sr_speed.launch (new!)
└─ src
├─ sender_speed.cpp (new!)
└─ receiver_speed.cpp (new!)
동작을 위한 소스 코드는 다음과 같다. 소스 코드는 C++로 작성하였다.
sender_speed.cpp
#include <ros/ros.h>
#include <std_msgs/String.h>
int main (int argc, char **argv) {
ros::init(argc, argv, "sender_speed");
ros::NodeHandle nh;
ros::Publisher pub = nh.advertise<std_msgs::String>("long_string", 1);
ros::Rate rate(1);
std_msgs::String hello_str;
int pub_size = 1000000; // 1M byte
//int pub_size = 5000000; // 5M byte
//int pub_size = 10000000; // 10M byte
//int pub_size = 20000000; // 20M byte
//int pub_size = 50000000; // 50M byte
std::string my_string(pub_size, '#');
while (ros::ok()) {
hello_str.data = my_string + ':' + std::to_string(ros::Time::now().toSec());
pub.publish(hello_str);
rate.sleep();
}
return 0;
}
receiver_speed.cpp
#include <ros/ros.h>
#include <std_msgs/String.h>
void callback(const std_msgs::String::ConstPtr& msg) {
const auto& data = msg->data;
size_t colon_pos = data.find(':');
if (colon_pos != std::string::npos) {
std::string payload = data.substr(0, colon_pos);
double arrival_time = std::stod(data.substr(colon_pos + 1));
double current_time = ros::Time::now().toSec();
double time_diff = current_time - arrival_time;
size_t string_size = payload.size();
ROS_INFO("%zu byte: %f second", string_size, time_diff);
ROS_INFO("speed: %f byte/s", static_cast<float>(string_size) / time_diff);
}
}
int main(int argc, char** argv) {
ros::init(argc, argv, "receiver_speed");
ros::NodeHandle nh;
ros::Subscriber sub = nh.subscribe("long_string", 10, callback);
ros::spin();
return 0;
}
sr_serial.launch
<launch>
<node pkg='msg_send' type='sender_speed' name='sender_speed_node'/>
<node pkg='msg_send' type='receiver_speed' name='receiver_speed_node' output='screen' />
</launch>
+) 앞선 예제와 마찬가지로 msg_send의 CMakeLists.txt에 조건들을 추가해줘야 한다.
https://leevision.tistory.com/80
[ROS 튜토리얼] ROS 노드 통신 프로그래밍
학습 내용 메시지를 통한 노드 간 통신 Teacher(Publisher)가 "my_topic"이라는 토픽을 Student(Subscriber)에게 전송하면 Student가 이 화면에 출력하는 토픽 통신 시스템을 구현해 보자. 언어는 C++를 사용한다.
leevision.tistory.com
먼저 1M byte를 전송하고 전송시간과 전송속도를 측정해보자. 실행 결과 전송시간은 약 0.005초이고 전송속도는 약 200 MBps인 것을 알 수 있다.
다음으로 5M byte를 전송하고 마찬가지로 전송시간과 속도를 측정해보자. 실행 결과 전송시간은 약 0.015초이고 전송속도는 약 300 MBps인 것을 알 수 있다.
마지막으로 50M byte를 전송하면 어떤 변화가 있는지 확인해보자. 실행 결과 전송시간은 약 0.2초이고 전송속도는 약 250 MBps인 것을 알 수 있다.
나머지 데이터 크기에 대해서도 실험을 진행하고 10개의 데이터에 대한 평균 전송시간과 평균 전송속도를 그래프로 표현하면 다음과 같은 결과를 얻을 수 있다.
그래프를 통해 전송 데이터의 사이즈가 증가할 수록 전송시간은 길어지고 전송속도는 대체로 낮아지는 것을 확인할 수 있다.
결론
이번 실습은 데이터의 크기에 따라 전송시간과 전송속도가 어떻게 변화하는지에 대해 알아보았다. 데이터의 크기를 바꿔보며 전송시간과 속도를 기록하고 이를 그래프로 확인하였을 때 전송하는 데이터의 크기가 커질수록 전송시간은 길어지고 전송속도는 대체로 낮아지는 결과를 보였다. 따라서 실제 시스템을 다루는 경우 현재 전송하려는 데이터의 크기를 확인하고 이에 따른 전송시간과 전송속도를 고려하여 설계할 필요가 있다.
'Study > ROS' 카테고리의 다른 글
[ROS 튜토리얼] 과제 #4. 주기적 발송에서 타임슬롯을 오버하면 어떻게 되는가? (0) | 2023.10.04 |
---|---|
[ROS 튜토리얼] 과제 #3. 도착하는 데이터를 미처 처리하지 못하면 어떻게 되는가? (0) | 2023.10.04 |
[ROS 튜토리얼] 과제 #1. 누락 없이 모두 잘 도착하는가? (0) | 2023.10.03 |
[ROS 튜토리얼] ROS 통신 중 발생하는 다양한 문제 상황과 해결 방법 (1) | 2023.10.03 |
[ROS 튜토리얼] ROS 노드 통신 프로그래밍 (0) | 2023.09.27 |