home search
Robotics
ROS
[Tutorial] 커스텀 메시지(custom msg) 만들기 (1)
2021. 12. 31

노드 간에 토픽을 주고 받을 때, 토픽의 자료형을 메시지라고 한다. 기존에 나와 있거나 내장되어 있는 메시지 타입을 사용할 수도 있지만, 경우에 따라 원하는 데이터만 퍼블리시 한다던지 혹은 데이터를 가공해 다시 퍼블리시 하는 등 또다른 메시지 타입을 만들고 싶을 때가 있다.

사용자가 임의로 만들어낸 메시지커스텀 메시지(custom message)라고 하며, 지금부터 커스텀 메시지를 만들고 사용하는 예를 알아본다.

또한 이어지는 포스팅에서는 GPS, IMU, LiDAR 등의 기기에서 받아들이는 토픽을 처리하는 방법을 알아볼텐데, 이 포스팅을 한 번쯤 보고 가야 이해가 쉬울 것이다.

🤔 커스텀 메시지의 필요성

위에서도 설명한 바 있지만, 노드&토픽 통신 중에 커스텀 메시지가 필요할 때가 종종 있다.

ROS에는 표준 메시지 타입들이 정의되어 있어, 소스 코드를 만들 때 이들을 import 해서 사용할 수 있다. 그러나 경우에 따라서는 다양한 타입의 자료형을 가지는 값들을 묶어 보내는 등 마음대로 조작을 하고 싶은 경우가 많다.

필자의 경우, GUI를 만들지 않았을 때 현재 구동중인 로봇(보트)의 속도, 목표점까지의 거리, 에러각 등의 상태를 그때그때 터미널 창에서 보고 싶었다. 하여 이 정보를 따로 담을 수 있는 메시지 파일을 만들어 하나의 토픽으로 전송하고, rostopic echo 명령어를 통해 모니터링한 바가 있었다.

또는 센서에서 받아온 값을 이리저리 조작하여 이를 publish 할 때 유용하게 사용될 수 있다. LiDAR로 예를 들면, 반경 내에서 감지하는 수많은 point 중에서, 가장 가까이 있는 point의 거리와 각도만을 걸러내, 자북을 기준으로 한 각도로 변환을 하고, 이를 토픽으로서 다른 노드로 전달할 수도 있다.

👀 메시지 타입 조회

이전 포스팅에서도 링크를 걸어두어 꽤 많이 보았을 것이다. std_msgs/Header 등 기존에 미리 정의된 메시지 타입들이 있다. 이를 조회할 수 있는 방법은 매우 간단하다.

구글 검색창에 ros + [메시지 타입]으로 검색하면 거의 대부분 첫 줄에 뜬다. 예를 들어 uint16이 궁금하다면 ros uint16이라 검색한다.

제일 첫 줄 ROS Documentation에 메시지 타입이 명시되어 있다.

해당 메시지가 어떤 패키지에 정의되어 있고, 어떤 파일이고, 상세한 정의가 나와있다. 다른 예는 아래와 같다.


🔨 커스텀 메시지 만들기

해당 포스팅에서는 Python을 이용해 제작하였다. C++로 제작하고 싶다면 앞선 포스팅 [ROS] 패키지 빌드와 노드 작성을 추가로 참고하여 C++ 스크립트 작성과 CMakeList.txt, package.xml 수정을 해야 한다.

(0) 순서

간단하게 커스텀 메시지를 만드는 순서는 다음과 같다.

  1. 구상하기: 노드와 토픽의 관계, 각 토픽이 가지고 갈 내용, 그리고 그 내용에 맞는 메시지 타입을 구상한다. 일종의 설계 단계이다.
  2. 패키지 만들기: 이번 실습을 진행할 패키지를 만든다.
  3. msg 파일 만들기: 각 토픽이 사용할 커스텀 메시지 파일을 만든다.
  4. 소스코드 만들기: 각 노드가 해당 메시지를 사용하는 소스코드를 만든다.
  5. package.xml, CMakeList.txt 파일 수정하기: 해당 .msg 파일을 잘 포함하도록 수정한다.
  6. 실행하기

(1) 구상하기

어떤 수의 제곱과 제곱근을 계산한 결과를 출력해볼 것이다. 총 3개의 노드와 그 사이를 오갈 2개의 토픽을 만들 것이다.

start_node에서 시작한 시각과 메시지 번호(1, 2, 3, …), 그리고 계산할 수를 결정한다. 계산할 수는 1~100 사이의 수로, 랜덤하게 선택한다. middle_node에서는 제곱과 제곱근 계산을 수행하고 이 결과를 덧붙여 다음 노드로 보낸다. end_node에서는 수행이 끝난 시각(middle_node로부터 메시지를 받은 시각)을 시작 시각에서 빼내 수행 시간(nsec 단위)를 계산하고, 제곱과 제곱근 계산 결과를 출력할 것이다.

(2) 패키지 만들기

본격적인 커스텀 메시지 만들기에 앞서, 이 기능을 수행할 패키지를 만들자. 패키지 제작의 상세한 내용은 이전 포스팅 [ROS] 패키지 빌드와 노드 작성에 있으므로 참고하고, 이번에는 절차만 소개하겠다.

catkin_ws/src에 실습 패키지를 만든다. 의존성 패키지로는 일단 python과 cpp 둘 다 넣었다.

$ cd /catkin_ws/src
$ catkin_create_pkg custom_msg_pkg std_msgs rospy roscpp

(3) msg 파일 만들기

위에서 구상한 대로, first_msg.msg, second_msg.msg 파일을 만들어 보자.

[1] 패키지 폴더 안에 msg 폴더를 만든다. cd /catkin_ws/src/custom_msg_pkg 하여 패키지 폴더로 이동한 뒤 mkdir msg를 해도 되고, GUI 상에서 [우클릭-새폴더]로 간단히 만들어도 된다.

[2] 해당 위치에 두 개의 메시지 파일을 만든다. 확장자를 반드시 msg로 해야 함에 주의하자. 필자는 Windows의 메모장 기능을 하는 우분투의 ‘텍스트 편집기’를 사용했다. VS Code로 작성해도 되고, 다른 에디터 어디든 가능하다.

first_msg.msg의 내용: time 형, 정수형 데이터를 사용했다.

time start_time
uint16 msg_seq
uint16 original_num

second_msg.msg의 내용: float 형 데이터를 추가로 사용했다.

time start_time
uint16 msg_seq
uint16 original_num
float32 square_num
float32 sqrt_num

(4) 소스코드 만들기

총 3개의 노드가 필요하므로 3개의 소스코드(스크립트)가 필요하다. 주의점은 아래와 같다.

  • ROS 표준 메시지와 마찬가지로, 메시지 및 자료형의 import 구문을 필히 작성해야 한다.
  • msg 파일에서 만든 자료형과 이름을 그대로 사용해야 한다.

start_node_script.py

#!/usr/bin/env python
#-*- coding:utf-8 -*-

import rospy		# ROS 라이브러리
import random		# 랜덤 수를 추출하기 위한 라이브러리
from custom_msg_pkg.msg import first_msg	# first_msg.msg 파일 불러오기

def main():
    # 퍼블리시 노드 초기화
    rospy.init_node('start_node', anonymous=False)
    
    # 퍼블리셔 변수
    pub = rospy.Publisher('first_topic', first_msg, queue_size=10)
    
    # 1초마다 반복(변수=rate)
    rate = rospy.Rate(1) #1Hz

    msg = first_msg()	# 메시지 변수 선언
    count = 1

    # 중단되거나 사용자가 강제종료(ctrl+C) 전까지 계속 실행
    while not rospy.is_shutdown():
        # 메시지 내용 담기
        ## start_time: 메시지를 생성해 publish 하는 시각
        ## msg_seq: 메시지 순서(번호)
        ## original_num: 계산의 대상이 될 수로, 1부터 100까지의 수 중 무작위로 하나를 뽑음
        msg.start_time = rospy.Time.now()
        msg.msg_seq = count
        msg.original_num = random.randrange(1,101)

        # 터미널에 출력
        rospy.loginfo("------")
        rospy.loginfo("Start Time(sec): %d", msg.start_time.secs)
        rospy.loginfo("Message Sequence: %d", msg.msg_seq)
        rospy.loginfo("Original Number: %d", msg.original_num)
                
        # 메시지를 퍼블리시
        pub.publish(msg)
        
        # 정해둔 주기(hz)만큼 일시중단
        rate.sleep()

        count += 1

if __name__ == '__main__':
    try:
        main()
    except rospy.ROSInterruptException:
        pass

middle_node.py 스크립트에는 클래스의 개념이 들어가 있다. 이전 포스팅에는 없던 내용이나, 사실 파이썬의 클래스 개념을 안다면 앞선 스크립트들과 별다를 것은 없다. 본 스크립트에서는 서브스크라이브 함수(callback 함수)를 클래스의 함수로 두고, 퍼블리시 기능을 함수화했다는 차이 정도가 있다.

middle_node_script.py

#!/usr/bin/env python
#-*- coding:utf-8 -*-

import rospy				# ROS 라이브러리
import random               # 랜덤 수를 추출하기 위한 라이브러리
import math
from custom_msg_pkg.msg import first_msg, second_msg
    # 서브스크라이브하는 first_msg.msg 파일과, 퍼블리시하는 second_msg.msg 파일 불러오기


class Calc:
    def __init__(self):
        rospy.Subscriber("/first_topic", first_msg, self.first_topic_callback)
        self.pub = rospy.Publisher("/second_topic", second_msg, queue_size=10)

        self.start_time = rospy.Time.now()
        self.msg_seq = 0
        self.original_num = 0
        self.square_num = 0
        self.sqrt_num = 0
        
    # 퍼블리셔 노드로부터 토픽을 받아들이는 콜백 함수
    def first_topic_callback(self, data):
        self.start_time = data.start_time
        self.msg_seq = data.msg_seq
        self.original_num = data.original_num
        self.square_num = math.pow(self.original_num, 2)
        self.sqrt_num = math.sqrt(self.original_num)

        # 받은 내용(data)를 터미널에 출력
        rospy.loginfo("------")
        rospy.loginfo("Message Sequence: %d", self.msg_seq)
        rospy.loginfo("Original Number: %d", self.original_num)
        rospy.loginfo("Square Number: %d", self.square_num)
        rospy.loginfo("Square Root Number: %d", self.sqrt_num)

    def second_msg_publish(self):
        msg = second_msg()	# 메시지 변수 선언

        # 메시지 내용 담기
        ## start_time: start_node가 메시지를 생성해 publish 하는 시각
        ## msg_seq: 메시지 순서(번호)
        ## original_num: 계산의 대상이 될 수
        ## square_num: original_num의 제곱
        ## sqrt_num: original_num의 제곱근
        msg.start_time = self.start_time
        msg.msg_seq = self.msg_seq
        msg.original_num = self.original_num
        msg.square_num = self.square_num
        msg.sqrt_num = self.sqrt_num

        self.pub.publish(msg)
    
def main():
    # 노드 초기화.
    rospy.init_node('middle_node', anonymous=False)
    rate = rospy.Rate(1)

    calc = Calc()
    while not rospy.is_shutdown():
        calc.second_msg_publish()
        rate.sleep()

if __name__ == '__main__':
    try:
        main()
    except rospy.ROSInterruptException:
        pass

end_node_script.py

#!/usr/bin/env python
#-*- coding:utf-8 -*-

import rospy				# ROS 라이브러리
from custom_msg_pkg.msg import second_msg    # 서브스크라이브하는 second_msg.msg 파일 불러오기


# 퍼블리셔 노드로부터 토픽을 받아들이는 콜백 함수
def second_topic_callback(data):
    # 받은 내용(data)를 터미널에 출력
    rospy.loginfo("------")
    rospy.loginfo("Processing Time(nsec): %d", rospy.Time.now().nsecs - data.start_time.nsecs)
    rospy.loginfo("Message Sequence: %d", data.msg_seq)
    rospy.loginfo("Original | Square | Square Root: %d | %d | %d", data.original_num, data.square_num, data.sqrt_num)
    
def main():
    rospy.init_node('end_node', anonymous=False)
    rospy.Subscriber("second_topic", second_msg, second_topic_callback)

    rospy.spin()

if __name__ == '__main__':
    main()

(5) package.xml, CMakeList.txt 파일 수정하기

메시지 파일이라는 새 요소가 추가되었으므로 실행 전 빌드하기 위해 사전 작업이 필요하다. 다시 언급하지만, Python 기준이므로 C++로 제작했다면 위에서 링크해둔 포스팅을 추가로 참고하여 수정하길 바란다.

[1] package.xml에 아래 내용을 추가한다. 이미 존재하고 있는 태그들의 순서(<build_depend>끼리, <exec_depend>끼리)에 맞게 넣는 것이 좋다.

<build_depend>message_generation</build_depend>

<exec_depend>message_runtime</exec_depend>

[2] CMakeList.txt의 아래 내용을 수정한다.

# message_generation 추가한다.
find_package(catkin REQUIRED COMPONENTS
  roscpp
  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_msg_pkg
  CATKIN_DEPENDS roscpp rospy std_msgs message_runtime
#  DEPENDS system_lib
)

# 주석을 풀고 스크립트 이름을 입력한다.
catkin_install_python(PROGRAMS
  src/start_node_script.py
  src/middle_node_script.py
  src/end_node_script.py
  DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

[3] 스크립트 파일에 실행 권한을 부여한다.

$ chmod +x start_node_script.py middle_node_script.py end_node_script.py

[4] 빌드를 진행한다.

$ catkin_make (또는 cm)

(6) 실행하기

이제 실행해보자. 네 개의 터미널 창이 일단 필요하며, 각각의 창에서 아래 명령어로 실행을 시켜보자. 스크립트의 경우 서브스크라이브하는 파일을 먼저 실행하는 것이 좋으므로, end - middle - start 순으로 실행시킨다.

$ roscore

$ rosrun custom_msg_pkg end_node_script.py

$ rosrun custom_msg_pkg middle_node_script.py

$ rosrun custom_msg_pkg start_node_script.py

마지막 사진을 보면 값들이 잘 주고받아지는 것을 확인할 수 있다.

하나의 터미널을 더 열어 rqt그래프를 통해 노드와 토픽 관계를 시각화해보자.

$ rqt_graph


참고 문헌

arrow_upward arrow_downward
loading