티스토리 뷰
1. 문제 : 협업해야 하는 노드를 순서대로 기동시킬 수 있는가?
4개의 sender 노드와 1개의 receiver노드를 기동한다.
sender 노드들은 receiver에게 메시지를 보내는데, 순서대로 receiver는 도착하도록 한다.
First - Second - Third - Fourth 이렇게 출력해야.
앞에 있는 노드가 움직이기 전에 먼저 움직여서는 안된다. (움직인다 = 토픽을 보내는 것)
1-1. 패키지 생성
order_test 이름의 패키지 생성.
cd xycar_ws/src/
catkin_create_pkg order_test std_msgs rospy
cm
1-3. 소스, 런치 파일
receiver.py
#!/usr/bin/env python
import rospy
from std_msgs.msg import String, Int32
start_ctl = 1
count1, count2, count3 = 0, 0, 0
def callback(msg):
global start_ctl, count1, count2, count3
if start_ctl < 2 and 'first' in msg.data:
count1 += 1
if count1 >= 5:
start_ctl = 2
if start_ctl < 3 and 'second' in msg.data:
count2 += 1
if count2 >= 5:
start_ctl = 3
if start_ctl < 4 and 'third' in msg.data:
count3 += 1
if count3 >= 5:
start_ctl = 4
print msg.data
rospy.init_node('receiver')
rate = rospy.Rate(1)
pub = rospy.Publisher('start_ctl', Int32)
sub = rospy.Subscriber('msg_to_receiver', String, callback)
while not rospy.is_shutdown():
pub.publish(start_ctl)
first.py
#!/usr/bin/env python
import rospy
from std_msgs.msg import String, Int32
printName = False
def callback(msg):
if msg.data >= 1:
global printName
printName = True
#print msg.data
rospy.init_node('first')
pub = False
#pub = rospy.Publisher('msg_to_receiver', String)
sub = rospy.Subscriber('start_ctl', Int32, callback)
rate = rospy.Rate(1)
while not rospy.is_shutdown():
if printName:
if not pub:
pub = rospy.Publisher('msg_to_receiver', String)
pub.publish('my name is ' + rospy.get_name())
rate.sleep()
second.py
#!/usr/bin/env python
import rospy
from std_msgs.msg import String, Int32
printName = False
def callback(msg):
if msg.data >= 2:
global printName
printName = True
#print msg.data
rospy.init_node('second')
pub = False
#pub = rospy.Publisher('msg_to_receiver', String)
sub = rospy.Subscriber('start_ctl', Int32, callback)
rate = rospy.Rate(1)
while not rospy.is_shutdown():
if printName:
if not pub:
pub = rospy.Publisher('msg_to_receiver', String)
pub.publish('my name is ' + rospy.get_name())
rate.sleep()
third.py
#!/usr/bin/env python
import rospy
from std_msgs.msg import String, Int32
printName = False
def callback(msg):
if msg.data >= 3:
global printName
printName = True
#print msg.data
rospy.init_node('third')
pub = False
#pub = rospy.Publisher('msg_to_receiver', String)
sub = rospy.Subscriber('start_ctl', Int32, callback)
rate = rospy.Rate(1)
while not rospy.is_shutdown():
if printName:
if not pub:
pub = rospy.Publisher('msg_to_receiver', String)
pub.publish('my name is ' + rospy.get_name())
rate.sleep()
fourth.py
#!/usr/bin/env python
import rospy
from std_msgs.msg import String, Int32
printName = False
def callback(msg):
if msg.data >= 4:
global printName
printName = True
#print msg.data
rospy.init_node('fourth')
pub = False
#pub = rospy.Publisher('msg_to_receiver', String)
sub = rospy.Subscriber('start_ctl', Int32, callback)
rate = rospy.Rate(1)
while not rospy.is_shutdown():
if printName:
if not pub:
pub = rospy.Publisher('msg_to_receiver', String)
pub.publish('my name is ' + rospy.get_name())
rate.sleep()
sr_order.launch
<launch>
<node name="receiver" pkg="order_test" type="receiver.py" output="screen"/>
<node name="first" pkg="order_test" type="first.py" output="screen"/>
<node name="second" pkg="order_test" type="second.py" output="screen"/>
<node name="third" pkg="order_test" type="third.py" output="screen"/>
<node name="fourth" pkg="order_test" type="fourth.py" output="screen"/>
</launch>
1-4. 빌드
실행권한 부여 및 빌드.
2. 현상 확인
roslaunch order_test sr_order.launch
first -> second -> third -> fouth 순으로 노드가 실행되는 것을 확인할 수 있다.
rqt_graph로 노드 관계 확인.
(1) 실행 직후
(2) first 노드 연결
(3) second 노드 연결
(4) third 노드 연결
(5) fourth 노드 연결
3. 고찰
• first -> second -> third -> fourth 순으로 노드가 순차적으로 통신하도록 하였다.
• 처음부터 노드의 publisher가 초기화 되어있는 것이 아닌, 각 노드가 receiver노드와 5번 이상 통신을 주고 받은 후에 다음 노드의 publisher가 생성되고, 통신을 하도록 구현하였다.
• 순서가 꼭 지켜져야 하는 협업에서 필요한 기능이다.
4. 참고자료
1) 한 노드에 publisher, subscriber 같이 생성
stackoverflow.com/questions/40508651/writing-a-ros-node-with-both-a-publisher-and-subscriber
Writing a ros node with both a publisher and subscriber?
I am currently trying to make a ROS node in Python which has both a subscriber and a publisher. I've seen examples where a message is published within the callback, but I want it to "constantly" p...
stackoverflow.com
'ROS' 카테고리의 다른 글
/dev/ttyUSB0 권한없음 오류 해결 과정 (삽질) (0) | 2021.01.14 |
---|---|
Ubuntu16.04 ROS Kinetic - 통신2) ROS 전송속도 측정 (0) | 2020.12.30 |
Ubuntu16.04 ROS Kinetic - 통신4) 타임슬롯 문제 (0) | 2020.12.28 |
Ubuntu16.04 ROS Kinetic - 통신3) 처리 지연 문제 (0) | 2020.12.28 |
Ubuntu16.04 ROS Kinetic - 원격통신 환경 구축 및 실습 (0) | 2020.12.24 |
- Total
- Today
- Yesterday
- VirtualBox
- roslaunch
- 포트인식문제
- sensehat
- HC-SR04
- 초음파센서
- Ubuntu16.04
- set backspace
- ROS
- Ubuntu20.04
- Python
- Mount
- 백준알고리즘
- Publisher
- C++
- 리눅스
- 원격 통신
- VMware
- vue/cli
- 윈도우
- 아두이노 IDE
- python3
- 윈도우 복구
- 8자주행
- 코드리뷰
- subscriber
- 우분투
- umount
- filesystem
- 프로그래머스
일 | 월 | 화 | 수 | 목 | 금 | 토 |
---|---|---|---|---|---|---|
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 |