티스토리 뷰

1. 문제 : 누락없이 모두 잘 도착하는가? 특히 처음과 끝.

sender가 보내는 메시지를 receiver가 처음부터 끝까지 누락없이 잘 받는지 확인하기.

못 받는다면, sender가 못 보내는 것인지? receiver가 못 받는 것인지?

Publisher와 Subscriber의 실질적인 통신 구축에 지연시간이 존재한다.

받는 쪽에서 준비가 안됐는데 토픽을 보내면? -> 못 받고 잃어버린다.

 

1-1. 파이썬 파일 작성

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()
	if count > 100:
		break

 

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()

 

1-2. 빌드 및 실행

빌드:

실행:

roslaunch로는 노드를 순서대로 실행시킬 수 없기 때문에 직접 실행한다.

receiver -> sender 노드 순.

터미널#1에서 

roscore

터미널#2에서

rosrun msg_send receiver_serial.py

터미널#3에서

rosrun msg_send sender_serial.py

 

2. 현상 확인

터미널#2에서 receiver는 아래와 같이 출력한다.

sender가 1부터 100까지 메시지를 보내고, receiver는 받은 메시지를 출력하도록 코드를 작성하였는데,

시작 토픽인 1은 출력되지 않는다. 다른 번호의 토픽들은 모두 잘 출력된다.

 

보내는 데이터를 1부터 500까지로 수정하여도,

시작 토픽 1은 출력되지 않고, 이외의 나머지 토픽들은 잘 수신하는 것을 확인할 수 있다.

 

3. 원인 분석

테스트의 편의를 위해 1~10까지의 토픽만을 발행한다.

 

3-1.

먼저 sender가 못 보내는 것인지, receiver가 못 받는 것인지를 확인하자.

여기서 새로운 터미널(#4)을 열어서 토픽을 확인하자.

rostopic echo /my_topic

터미널#2와 터미널#4를 모두 실행한 후에 터미널#3에서 sender노드를 실행한다.

receiver_serial.py 실행 결과 rostopic echo /my_topic 실행 결과

몇 번의 실험을 더 해보았지만, 결과는 같았다.

이렇게 되면 receiver가 토픽을 못 받는 것이 아니라, sender가 토픽을 발행하지 못하는 것임을 알 수 있다.

 

4. 해결책

Publisher객체를 생성할 때 latch라는 속성이 있다. 디폴트값은 False인데, True로 해주면, 발행된 마지막 메시지에 대한 참조가 저장되고, 연결된 후에 구독자에게 전송된다.

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, latch=True)

rate = rospy.Rate(2)
count = 1

while not rospy.is_shutdown():
	pub.publish(count)
	count += 1
	rate.sleep()
	if count > 100:
		break

 

5. 적용 결과

터미널#1(roscore), 터미널#2(rosrun msg_send receiver_serial.py), 터미널#4(rostopic echo /my_topic)를 실행 후

터미널#3에서 rosrun msg_send sender_serial.py 를 실행한 결과는 아래와 같다.

receiver_serial.py 실행 결과 rostopic echo /my_topic 실행 결과

이제 처음부터 끝까지 모든 토픽을 누락없이 전달하는 것을 확인할 수 있다.

 

6. 참고자료

wiki.ros.org/rospy/Overview/Publishers%20and%20Subscribers

 

rospy/Overview/Publishers and Subscribers - ROS Wiki

Publishing to a topic See also: rospy.Publisher Code API You can create a handle to publish messages to a topic using the rospy.Publisher class. The most common usage for this is to provide the name of the topic and the message class/type of the topic. You

wiki.ros.org

댓글
공지사항
최근에 올라온 글
최근에 달린 댓글
Total
Today
Yesterday
링크
«   2025/04   »
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
글 보관함