[ROS 튜토리얼] Custom Message (msg) 생성하기

Create ROS Custom Message

1. package 생성하기

 package 생성에 대한 내용은 이전 포스트에서 다루었다.

2. msg 생성

생성해둔 package폴더 내에 msg폴더를 만들어준다. 그리고 custom message를 작성한다.

$ roscd beginner_tutorials
$ mkdir msg
$ echo "int64 num" > msg/Num.msg

나의 경우, 아래와 같은 msg 파일을 생성해주었다.

# bbox.msg

float32 x_min
float32 y_min
float32 z_min
float32 x_max
float32 y_max
float32 z_max

3. source code 작성

Python이나 C++ 중 원하는 언어로 코드를 작성한다. 이번 포스트에서는 Python 언어로 작성하고자 한다.

# test.py

from beginner_tutorials.msg import bbox

...

4. CMakeLists.txt 및 package.xml 수정

 4.1 package.xml

package.xml에서 주석처리가 되어있는 아래 두 라인에 대해 주석을 해제해준다.

<build_depend>message_generation</build_depend>
<exec_depend>message_runtime</exec_depend>
 4.2 CMakeLists.txt
find_package(catkin REQUIRED COMPONENTS
   roscpp
   rospy
   std_msgs
   message_generation # 추가된 라인
)

add_message_files(
   FILES
   bbox.msg # 생성한 .msg file
)

generate_messages(
   DEPENDENCIES
   std_msgs # custom message가 의존하고있는 message 추가
)

catkin_package(
   CATKIN_DEPENDS message_runtime
)

5. Reference

Leave a Reply

Your email address will not be published. Required fields are marked *