노드 통신을 위한 패키지 만들기
노드간 통신 개요
노드
→ 토픽
을 주고 받는 주체
Publisher
→ 토픽
을 발행
Subscriber
→ 토픽
을 받음
토픽
→ 전달되는 메시지, 데이터 등등…
패키지 만들기
cd ~/xycar_ws/src
catkin_create_pkg msg_send std_msgs rospy
cd msg_send
mkdir launch
cm
토픽을 발행하고 구독하는 코드 작성
- 토픽 이름 →
my_topic
- 위치 →
~/xycar_ws/src/msg_send/src
- Publisher →
teacher.py
#!/usr/bin/env python
import rospy
from std_msgs.msg import String
rospy.init_node('teacher')
pub = rospy.Publisher('my_topic', String)
rate = rospy.Rate(2)
while not rospy.is_shutdown():
pub.publish('call me please')
rate.sleep()
#!/usr/bin/env python
import rospy
from std_msgs.msg import String
def callback(msg):
print msg.data
rospy.init_node('student')
sub = rospy.Subscriber('my_topic', String, callback)
rospy.spin()
- launch 파일 → m_send.launch
~/xycar_ws/src/msg_send/launch
<launch>
<node pkg="msg_send" type="teacher.py" name="teacher"/>
<node pkg="msg_send" type="student.py" name="student" output="screen"/>
</launch>
cm
chmod +x teacher.py student.py
roslaunch msg_send m_send.launch
1:N, N:1, N:N 통신
- 이번에는
int32
타입 메시지를 주고받는 코드
- Publisher →
teacher_int.py
#!/usr/bin/env python
import rospy
from std_msgs.msg import Int32
rospy.init_node('teacher')
pub = rospy.Publisher('my_topic', Int32)
rate = rospy.Rate(2)
count = 1
while not rospy.is_shutdown():
pub.publish(count)
count = count + 1
rate.sleep()
- Subscriber →
student_int.py
#!/usr/bin/env python
import rospy
from std_msgs.msg import Int32
def callback(msg):
print msg.data
rospy.init_node('student')
sub = rospy.Subscriber('my_topic', Int32, callback)
rospy.spin()
- launch 파일 → m_send_1n.launch
<launch>
<node pkg="msg_send" type="teacher_int.py" name="teacher"/>
<node pkg="msg_send" type="student_int.py" name="student1" output="screen"/>
<node pkg="msg_send" type="student_int.py" name="student2" output="screen"/>
<node pkg="msg_send" type="student_int.py" name="student3" output="screen"/>
</launch>
나만의 메시지 만들기
string
, int32
등 자료형이 아닌 고유한 형식의 메시지를 보내 보자
Custom Message
mkdir msg
cd msg
gedit my_msg.msg
====================
string first_name
string last_name
int32 age
int32 score
string phone_number
int32 id_number
===================
cd ~/xycar_ws/src/msg_send
gedit package.xml
<build_depend>message_generation</build_depend>
<exec_depend>message_runtime</exec_depend>
gedit CMakeLists.txt
=====================
find_package(catkin REQUIRED COMPONENTS
rospy
std_msgs
)
add_message_files(
FILES
)
generate_messages(
DEPENDENCIES
std_msgs
)
catkin_package(
CATKIN_DEPENDS message_runtime
)
=====================
cm
rosmsg show my_msg