티스토리 뷰

ROS_통신2_전송속도측정.pptx
0.27MB

 

1. 문제 : 데이터 크기에 따른 전송속도 측정

1초에 1번씩 다양한 용량의 long_string을 발행한다. 문자열은 #으로 가득 채운다.

발행하는 토픽 이름은 long_string, 타입은 String (문자열)

1M, 5M, 10M, 20M, 50M byte전송한다.

receiver측에서 수신속도 계산한다.

송수신 속도의 단위 : Bps (Byte/sec) 로 측정한다.

 

1-1. 소스 파일, 런치파일

sender_speed.py

#!/usr/bin/env python

import rospy
import time
from std_msgs.msg import String, Int32

rospy.init_node('Sender')
pub = rospy.Publisher('long_string', String, queue_size=10)
pubTime = rospy.Publisher('time', Int32, queue_size=10)
rate = rospy.Rate(1)

length = rospy.get_param('~length')

while not rospy.is_shutdown():
	pubTime.publish(time.time())
	pub.publish('#'*length)
	rate.sleep()

 

receiver_speed.py

#!/usr/bin/env python

import rospy
import time
from std_msgs.msg import String, Int32

sendtime = 0

def callback(msg):
	recvtime = time.time()
	print len(msg.data), 'byte:\t', "{:.4f}".format((recvtime - sendtime)), 'seconds', "\t\tspeed:  {:.2f}".format(len(msg.data)/(recvtime-sendtime)), 'bytes/s' 
	print

def callbackTime(msg):
	global sendtime
	sendtime = msg.data

rospy.init_node('Receiver')

subTime = rospy.Subscriber('time', Int32, callbackTime)
sub = rospy.Subscriber('long_string', String, callback)
rospy.spin()

 

sr_speed.launch

 

<launch>
	<node pkg="msg_send" type="sender_speed.py" name="sender1M">
		<param name="length" value="1000000"/>
	</node>
	<node pkg="msg_send" type="sender_speed.py" name="sender5M">
		<param name="length" value="5000000"/>
	</node>
	<node pkg="msg_send" type="sender_speed.py" name="sender10M">
		<param name="length" value="10000000"/>
	</node>
	<node pkg="msg_send" type="sender_speed.py" name="sender20M">
		<param name="length" value="20000000"/>
	</node>
	<node pkg="msg_send" type="sender_speed.py" name="sender50M">
		<param name="length" value="50000000"/>
	</node>
	<node pkg="msg_send" type="receiver_speed.py" name="receiver" output="screen"/>
</launch>

 

1-2. 빌드

cm

 

2. 현상 확인

roslaunch msg_send sr_speed.launch

위 명령을 통해 실행한 결과는 아래와 같다.

전송 바이트와 수신속도를 표로 나타내면 아래와 같다.

전송 바이트 (단위: bytes) 수신 속도 (단위 Bps)
1M 1.6M 1.6M 1.5M 1.6M
5M 7.4M 7.4M 4.6M 6.9M
10M 13.8M 13.8M 9.8M 13.4M
20M 31.4M 31.4M 18.3M 31.2M
50M 49.0M 51.4M 48.9M 41.2M

각 전송 바이트마다 수신 속도는 비슷하다.

또 전송 바이트가 증가할수록 수신 속도 역시 증가하는 정비례관계를 가진다.

그래서 총 전송시간은 비슷한데, 10Mbytes가 넘어가면 보통 1초가 넘고, 10Mbytes이하이면 평균적으로 약 0.7초가 걸린다.

 

3. 고찰

각 전송 바이트마다 수신 속도가 비슷하게 측정되었다.

수신 속도는 전송 바이트가 증가할 수록 증가하는, 정비례 관계를 갖는다.

 

4. 참고자료

1) 파이썬 소수점 출력

datascience.stackexchange.com/questions/64521/why-i-get-attributeerror-float-object-has-no-attribute-3f

 

Why I get AttributeError: 'float' object has no attribute '3f'?

I am getting this error: AttributeError: 'float' object has no attribute '3f' I don't understand why I am getting it, I am following the example straight from the book "applied text analysis" The

datascience.stackexchange.com

댓글
공지사항
최근에 올라온 글
최근에 달린 댓글
Total
Today
Yesterday
링크
«   2025/05   »
1 2 3
4 5 6 7 8 9 10
11 12 13 14 15 16 17
18 19 20 21 22 23 24
25 26 27 28 29 30 31
글 보관함