지난 1편 포스팅 [Tutorial] 커스텀 메시지(custom msg) 만들기 (2)에 이어 오늘은 2편으로 ‘배열(리스트) 자료형을 포함한’ 커스텀 메시지를 만들어볼 것이다.
가끔 표준 메시지형을 보다가 자료형 뒤에 []이 붙은 것을 확인할 수 있는데, 그것이 배열형이라는 의미이다. float32[]라면 float32형의 숫자 여러 개가 배열로 전달된다는 뜻이다.

여러 번 소개했지만, IMU에서 퍼블리시하는 메시지 중 하나인 sensor_msgs/Imu를 살펴보면, float64[9]라고 되어 있다. float64, 즉 실수 형 숫자 9개로 이루어진 데이터란 뜻이다. 실제로 이 자료형을 쓰고 있는 데이터들은 x, y, z 축에 대한 공분산을 나타내고 있다.

또 다른 예를 보자. 여기서는 배열의 크기가 지정되지 않고 그저 []라고만 되어 있다. 배열의 크기가 매번 바뀌는 경우 이렇게 지정할 수도 있다.
순서는 앞선 포스팅과 동일하므로 자세한 설명은 생략하고 절차만 나타내겠다.
msg 파일 만들기package.xml, CMakeList.txt 파일 수정하기
메시지의 번호와 (x, y) 좌표 여러 개의 정보를 한 토픽에 담아 전송해보자.
단순히 data_node에서는 값을 퍼블리시하고 print_node에서는 값을 받아 터미널에 출력하기만 할 것이다. 퍼블리시/서브스크라이브 되는 토픽의 이름은 poins이다.
메시지를 보면, 토픽 points에서 사용하는 자료형 Locations에서는 (x, y) 좌표인 location을 Coordinate라는 자료형의 배열로 하고 있다. 메시지형 Coordinate는 각각 실수형의 x, y 값을 가지고 있다. 직관적으로 이해하자면 [x, y]라고 표시했을 때, location = [[1, 2], [3, 4], [6, 7], [7, 8],...]가 된다는 의미이다.
이번 포스팅에서도 파이썬을 기준으로 설명할 예정이다. C++로 만들 경우 [ROS] 패키지 빌드와 노드 작성 을 참고하자.
/catkin_ws/src로 이동해 패키지를 생성한다.
$ cd /catkin_ws/src
$ catkin_create_pkg custom_msg2_pkg std_msgs rospy

패키지 디렉토리 내에 msg 디렉토리를 만들고 그 안에 두 개의 메시지 파일 Locations.msg, Coordinate.msg를 만든다.

Locations.msg
uint16 msg_seq
Coordinate[] location
Coordinate.msg
int16 x
int16 y
두 개의 노드에 대해 각각 스크립트를 만든다.
data_node_script.py
#!/usr/bin/env python
#-*- coding:utf-8 -*-
from __future__ import print_function #print함수의 end 옵션 사용 위함
import rospy
import random
from custom_msg2_pkg.msg import Locations, Coordinate
def main():
rospy.init_node('data_node', anonymous=False)
pub = rospy.Publisher('points', Locations, queue_size=10)
rate = rospy.Rate(1)
count = 1
while not rospy.is_shutdown():
loc = Locations()
loc.msg_seq = count # 메시지 번호
loc_size = random.randrange(1,5) # 좌표 개수를 랜덤으로 1~4개 중 택
for i in range(loc_size):
x_value = random.randrange(-50,51) # x좌표
y_value = random.randrange(-50,51) # y좌표
loc.location.append(Coordinate(x=x_value, y=y_value))
# Coordinate 형으로 배열에 추가함
# 전송할 토픽을 출력해본다.
print("-"*10)
print("Message Sequence:", loc.msg_seq)
print("Locations:")
for i in range(loc_size):
print("(", loc.location[i].x, ", ", loc.location[i].y, ")", end=', ')
print("\n")
pub.publish(loc)
rate.sleep()
count += 1
if __name__ == '__main__':
try:
main()
except rospy.ROSInterruptException:
pass
print_node_script.py
#!/usr/bin/env python
#-*- coding:utf-8 -*-
from __future__ import print_function
import rospy
from custom_msg2_pkg.msg import Locations, Coordinate
def points_topic_callback(data):
loc_size = len(data.location)
print("-"*10)
print("Message Sequence:", data.msg_seq)
print("Locations:")
for i in range(loc_size):
print("(", data.location[i].x, ", ", data.location[i].y, ")", end=', ')
print("\n")
def main():
rospy.init_node('print_node', anonymous=False)
rospy.Subscriber("points", Locations, points_topic_callback)
rospy.spin()
if __name__ == '__main__':
main()
package.xml, CMakeList.txt 파일 수정하기[1] package.xml에 아래 내용을 추가한다.
<build_depend>message_generation</build_depend>
<exec_depend>message_runtime</exec_depend>
[2] CMakeList.txt에 아래 내용을 수정한다.
# message_generation을 추가한다.
find_package(catkin REQUIRED COMPONENTS
rospy
std_msgs
message_generation
)
# add_message_files의 주석을 풀고 수정한다.
add_message_files(
FILES
Locations.msg
Coordinate.msg
)
# generate_messages의 주석을 푼다.
generate_messages(
DEPENDENCIES
std_msgs
)
# LIBRARIES, CATKIN_DEPENDS의 주석을 풀고, message_runtime을 추가한다.
catkin_package(
# INCLUDE_DIRS include
LIBRARIES custom_msg2_pkg
CATKIN_DEPENDS rospy std_msgs message_runtime
# DEPENDS system_lib
)
# 주석을 풀고 스크립트 이름을 입력한다.
catkin_install_python(PROGRAMS
src/data_node_script.py
src/print_node_script.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)
[3] 스크립트 파일에 실행 권한을 부여한다.
$ chmod +x data_node_script.py print_node_script.py
[4] 빌드를 진행한다.
$ catkin_make (또는 cm)
roscore를 켤 창, data_node_script.py를 켤 창, print_node_script.py를 켤 창, 이렇게 총 3개의 터미널 창이 필요하다. 서브스크라이브 되는 스크립트가 먼저 실행되는 것이 편리하다.
$ roscore
$ rosrun custom_msg2_pkg data_node_script.py
$ rosrun custom_msg2_pkg print_node_script.py


rqt 그래프와 토픽 리스트, 메시지 내용도 확인할 수 있다.
$ rqt_graph

$ rostopic list
$ rostopic echo /points
