ROS

ROS 노드 통신 문제

Jagbbum 2023. 10. 3. 15:12

1.  노드간 동기화 문제

publisher와 subscriber의 지연시간 존재

rosrun msg_send receiver_serial.py
rosrun msg_send sender_serial.py
2
3
4
5
6
7
8
9
10
11
12
13
14
15

sender가 receiver에게 1부터 1씩 커지는 수를 보내는 경우 위와 같이 1을 못 받는 경우가 발생할 수 있다.

 

문제 발생 해결 : 

1) 노드가 등록이 됐는지 확인

 get_num_connections() // 연결된 노드의 수를 확인한다.

2) 파이썬

while(pub.get_num_connections() == 0): // 연결된 노드의 수가 0일 때 루프에 빠짐

 만약 1:n 통신일 때에는 아래와 같이 사용하면 된다.

while(pub.get_num_connections() != n):

 

#sender_serial.py
#!/usr/bin/env python

import rospy
from std_msgs.msg import Int32

rospy.init_node('sender_serial')

pub = rospy.Publisher('my_topic', Int32)

rate = rospy.Rate(2)
count = 1

while not rospy.is_shutdown():
    pub.publish(count)
    count +=1
    rate.sleep()
# receiver_serial.py
#!/usr/bin/env python

import rospy
from std_msgs.msg import Int32

def callback(msg):
    print msg.data

rospy.init_node('receiver_serial')

sub = rospy.Subscriber('my_topic',Int32,callback)

rospy.spin()

 

2. 전송속도

통신 과정에서 데이터의 크기가 커지면 전송 속도가 달라진다.

이것을 알아보기 위하여 코드를 짜서 확인해 본다.

 

pub_size = 1000000
#pub_size = 5000000
#pub_size = 10000000
#pub_size = 20000000
#pub_size = 50000000

위와 같이 Pub의 사이즈에 따른 속도 차이를 확인해본다.

[INFO] [1696245291.418447]: 1000000byte: 0.00999999046326second
[INFO] [1696245291.421685]: speed : 100000095.368byte/s
[INFO] [1696245635.353146]: 5000000byte: 0.00999999046326second
[INFO] [1696245635.354607]: speed : 500000476.838byte/s
[INFO] [1696245670.961228]: 10000000byte: 0.039999961853second
[INFO] [1696245670.962741]: speed : 250000238.419byte/s
[INFO] [1696245695.068516]: 20000000byte: 0.039999961853second
[INFO] [1696245695.069853]: speed : 500000476.838byte/s
[INFO] [1696245719.133678]: 50000000byte: 0.129999876022second
[INFO] [1696245719.135953]: speed : 384615751.414byte/s

위와 같이 데이터의 크기에 따라서 소요되는 시간이 달라지는 것을 확인할 수 있다.

 

# sender_speed.py
#!/usr/bin/env python

import rospy
from std_msgs.msg import String

name = "sender"
pub_topic = "long_string"

rospy.init_node(name, anonymous = True)
pub = rospy.Publisher(pub_topic, String, queue_size = 1)

hello_str = String()
rate = rospy.Rate(1)

#pub_size = 1000000
#pub_size = 5000000
#pub_size = 10000000
#pub_size = 20000000
pub_size = 50000000

my_stirng = ""

for i in range(pub_size):
    my_stirng += "#"

while not rospy.is_shutdown():
    hello_str.data = my_stirng + ":" + str(rospy.get_time())
    pub.publish(hello_str)
    rate.sleep()
# receiver_speed.py
#!/usr/bin/env python

import rospy
from std_msgs.msg import String

name = "receiver"
sub_topic = "long_string"

def callback(data):
    current_time = str(rospy.get_time())
    arrival_data = str(data.data).split(":")

    time_diff = float(current_time) - float(arrival_data[1])
    string_size = len(arrival_data[0])
    rospy.loginfo(str(string_size) + "byte: " +str(time_diff) + "second")
    rospy.loginfo("speed : "+ str(float(string_size)/time_diff) + "byte/s")

rospy.init_node(name, anonymous=True)
rospy.loginfo("init")
rospy.Subscriber(sub_topic, String, callback)
rospy.spin()

3. 처리 지연 문제

도착하는 데이터를 처리하지 못하면 데이터를 못 받는 경우가 생긴다.

[INFO] [1696249562.595227]: callback is being processed
2
[INFO] [1696249567.603922]: callback is being processed
4940
[INFO] [1696249572.615499]: callback is being processed
9890
[INFO] [1696249577.628136]: callback is being processed
14805
[INFO] [1696249582.648279]: callback is being processed
19837
[INFO] [1696249587.658202]: callback is being processed
24784
[INFO] [1696249592.664495]: callback is being processed
29782
[INFO] [1696249597.673639]: callback is being processed
34756
[INFO] [1696249602.680553]: callback is being processed
39650

위와 같이 queue의 사이즈가 1일 때는 데이터의 손실이 있다.

이 때 queue의 사이즈를 10000으로 바꾸면 아래와 같이 손실없이 데이터를 받아온다.

[INFO] [1696249673.654558]: callback is being processed
3
[INFO] [1696249678.661368]: callback is being processed
4
[INFO] [1696249683.663770]: callback is being processed
5
[INFO] [1696249688.669716]: callback is being processed
6
# sender_overflow.py
#!/usr/bin/env python

import rospy
from std_msgs.msg import Int32

name = "sender"
pub_topic ="my_topic"

rospy.init_node(name)
pub = rospy.Publisher(pub_topic, Int32, queue_size=1)

rate = rospy.Rate(1000)
count = 1

while(pub.get_num_connections() == 0):
    continue

while not rospy.is_shutdown():
    pub.publish(count)
    count +=1
    rate.sleep()
# receiver_overflow.py
#!/usr/bin/env python

import rospy
from std_msgs.msg import Int32

name = "receiver"
sub_topic = "my_topic"

def callback(data):
    rospy.loginfo("callback is being processed")
    rospy.sleep(5)
    print(data.data)

rospy.init_node(name)
rospy.Subscriber(sub_topic, Int32, callback, queue_size=10000)
rospy.spin()

 

4. 타임 슬롯 문제

주기적 발송에서 타임슬롯을 오버하는 경우가 생길 수 있다.

아래는 Rate를 5로하여 1초에 5번의 반복이 생기는 경우에서 슬롯의 크기를 조절해본 것이다.

>>1000
('spend time >> ', 0.0522, 's')
('sleep time >> ', 0.1485, 's')
('spend time >> ', 0.0597, 's')
('sleep time >> ', 0.1413, 's')
('spend time >> ', 0.0731, 's')
('sleep time >> ', 0.1262, 's')
('spend time >> ', 0.0754, 's')
('sleep time >> ', 0.1238, 's')
('spend time >> ', 0.073, 's')
('sleep time >> ', 0.1274, 's')
-------------------------------------------------
('total time >> ', 1.0007, 's')

>>3000
('spend time >> ', 0.1873, 's')
('sleep time >> ', 0.013, 's')
('spend time >> ', 0.2994, 's')
('sleep time >> ', 0.0001, 's')
('spend time >> ', 0.2956, 's')
('sleep time >> ', 0.0001, 's')
('spend time >> ', 0.1773, 's')
('sleep time >> ', 0.0003, 's')
('spend time >> ', 0.2263, 's')
('sleep time >> ', 0.0002, 's')
-------------------------------------------------
('total time >> ', 1.1997, 's')

>>4000
('spend time >> ', 0.3152, 's')
('sleep time >> ', 0.0001, 's')
('spend time >> ', 0.3067, 's')
('sleep time >> ', 0.0001, 's')
('spend time >> ', 0.2845, 's')
('sleep time >> ', 0.0001, 's')
('spend time >> ', 0.2971, 's')
('sleep time >> ', 0.0001, 's')
('spend time >> ', 0.2637, 's')
('sleep time >> ', 0.0002, 's')
-------------------------------------------------
('total time >> ', 1.4679, 's')

>>10000
('spend time >> ', 0.6567, 's')
('sleep time >> ', 0.0001, 's')
('spend time >> ', 0.7787, 's')
('sleep time >> ', 0.0002, 's')
('spend time >> ', 0.7851, 's')
('sleep time >> ', 0.0001, 's')
('spend time >> ', 0.6648, 's')
('sleep time >> ', 0.0002, 's')
('spend time >> ', 0.6984, 's')
('sleep time >> ', 0.0001, 's')
-------------------------------------------------
('total time >> ', 3.5843, 's')

위의 상황에서 슬롯의 크기가 1초에 5번의 반복이 지켜지지 않아 시간을 초과하고 sleep을 하지 못하고 바로 다음 번의 동작을 하는 것을 볼 수 있다.

#!/usr/bin/env python

import rospy
import time
from std_msgs.msg import Int32

def do_job(time):
    for i in range(0,time):
        i +=1
        pub.publish(i)

def list_append_time():
    start.append(start_time)
    end.append(end_time)
    sleep.append(sleep_time)

rospy.init_node('teacher')
pub = rospy.Publisher('my_topic', Int32, queue_size=0)
rate = rospy.Rate(5)

while not rospy.is_shutdown():
    start =[]
    end = []
    sleep = []
    num = input(">>")
    rate.sleep()
    total_start = time.time()

    for j in range(0,5):
        start_time = time.time()
        do_job(num)
        end_time = time.time()

        rate.sleep()
        sleep_time = time.time()
        list_append_time()
    total_end = time.time()

    for t in range(0,5):
        sleep[t] = sleep[t] - end[t]
        end[t] = end[t] - start[t]

    for result in range(0,5):
        print("spend time >> ", round(end[result],4),'s')
        print("sleep time >> ", round(sleep[result],4), 's')
    print('-------------------------------------------------')
    print("total time >> ", round((total_end-total_start),4),'s')

5. 노드의 순차 실행

협업 시 노드를 순서대로 구동시킬 수 있어야 한다.

data: "first:go"
---
data: "second:go"
---
data: "third:go"
---
data: "fourth:go"
data: "my name is first"
---
data: "my name is second"
---
data: "my name is third"
---
data: "my name is fourth"

 

위와 같이 순서대로 topic을 받고 다시 순서대로 topic을 주는 형태를 만들어야한다.

#! /usr/bin/env python

import rospy
from std_msgs.msg import String

name = "receiver"
pub_topic = "start_ctl"
sub_topic = "msg_to_receiver"

def callback(data):
    rospy.loginfo("i heard %s", data.data)

rospy.init_node(name)
rospy.Subscriber(sub_topic, String, callback)
pub = rospy.Publisher(pub_topic, String, queue_size = 1)

rate = rospy.Rate(10)
hello_str = String()
rospy.sleep(1)

sq = ["first", "second", "third", "fourth"]
pub_msg = String()

for i in sq:
    pub_msg.data = i + ":go"
    pub.publish(pub_msg)
    rospy.sleep(3)

rospy.spin()
#!/usr/bin/env python

import rospy
from std_msgs.msg import String

name = "first"  # second, third, fourth 
pub_topic = "msg_to_receiver"
sub_topic = "start_ctl"

OK = None

def ctl_callback(data):
    global OK
    OK = str(data.data)

rospy.init_node(name)
rospy.Subscriber(sub_topic, String, ctl_callback)

while True:
    if OK == None:
        continue
    d = OK.split(":")
    if (len(d) == 2) and (d[0] == name) and (d[1] == "go"): # 자신의 이름과 topic의 이름이 같을 때
        break
pub = rospy.Publisher(pub_topic, String, queue_size = 1)
rate = rospy.Rate(2)
hello_str = String()

while not rospy.is_shutdown():
    hello_str.data = "my name is " + name
    pub.publish(hello_str)
    rate.sleep()