이번 글에서는 ROS 2에서 직접 메시지 타입을 정의하고, 이를 Python 노드에서 사용하는 방법을 정리해 보겠습니다. 예제 목표는 turtlesim의 위치 정보와 속도 명령 정보를 각각 구독한 뒤, 하나의 사용자 정의 메시지로 묶어 출력하는 것입니다.
최종적으로 다룰 내용은 다음과 같습니다.
- 사용자 정의 메시지 패키지 생성
- .msg 파일 작성
- CMakeLists.txt, package.xml 설정
- ros2 interface show로 메시지 확인
- /turtle1/pose 토픽 구독
- /turtle1/cmd_vel 토픽 구독
- 두 토픽 데이터를 하나의 메시지 구조체에 저장
- colcon build --packages-select로 특정 패키지만 빌드
1. 메시지 전용 패키지를 따로 만드는 이유
ROS 2에서는 토픽으로 데이터를 주고받을 때 메시지 타입이 반드시 필요합니다. 기본 메시지 타입으로 충분한 경우도 있지만, 실제 로봇 개발에서는 여러 데이터를 하나로 묶어 보내야 하는 경우가 많습니다.
예를 들어 로봇의 현재 위치, 목표 속도, 센서 상태, 제어 명령 등을 하나의 데이터 구조로 정의하면 노드 간 통신이 훨씬 명확해집니다.
이번 예제에서는 다음 값을 하나의 메시지로 묶습니다.
cmd_vel_linear
cmd_vel_angular
pose_x
pose_y
linear_vel
angular_vel
여기서 cmd_vel_linear, cmd_vel_angular는 /turtle1/cmd_vel 토픽에서 받아오는 속도 명령 값이고, pose_x, pose_y, linear_vel, angular_vel은 /turtle1/pose 토픽에서 받아오는 거북이의 상태 값입니다.
2. 사용자 정의 메시지 패키지 생성
먼저 ROS 2 워크스페이스의 src 폴더로 이동합니다.
cd ~/ros2_study/src

메시지 전용 패키지를 생성합니다.
ros2 pkg create --build-type ament_cmake my_first_package_msgs


여기서 중요한 점은 ament_python이 아니라 ament_cmake를 사용한다는 것입니다.
ROS 2에서 .msg, .srv, .action 같은 인터페이스 파일을 생성하려면 일반적으로 ament_cmake 기반 패키지를 따로 두는 방식이 가장 깔끔합니다.
생성 후 구조는 대략 다음과 같습니다.
my_first_package_msgs/
├── CMakeLists.txt
├── include/
├── package.xml
└── src/

이제 여기에 메시지 정의 파일을 추가합니다.
3. msg 폴더와 CmdAndPoseVel.msg 만들기
패키지 안으로 이동합니다.
cd ~/ros2_study/src/my_first_package_msgs

msg 폴더를 생성합니다.
mkdir msg

msg 폴더 안에 메시지 파일을 만듭니다.
touch msg/CmdAndPoseVel.msg

파일 이름은 대소문자를 구분합니다.
ROS 2 메시지 파일은 보통 PascalCase 형식으로 작성합니다.
CmdAndPoseVel.msg
파일 안에는 다음 내용을 작성합니다.
src 폴더로 이동하여 VS Code를 실행합니다.
cd ~/ros2_study/src
code .
왼쪽 "EXPLORER" 창에서 CmdAndPoseVel.msg를 클릭하고 편집창에 불러옵니다.

아래의 내용을 추가합니다. Ctrl+s를 입력하여 저장을 완료합니다.
float32 cmd_vel_linear
float32 cmd_vel_angular
float32 pose_x
float32 pose_y
float32 linear_vel
float32 angular_vel

이 메시지는 총 6개의 float32 필드를 갖습니다.
4. CMakeLists.txt 설정
my_first_package_msgs/CMakeLists.txt 파일을 열고 메시지 생성을 위한 설정을 추가합니다.
아래의 그림은 패키지를 생성하면 자동으로 만들어지는 기본 코드들입니다.

여기에 아래와 같은 코드를 추가합니다. 핵심 코드는 다음과 같습니다.
find_package(rosidl_default_generators REQUIRED)
rosidl_generate_interfaces(${PROJECT_NAME}
"msg/CmdAndPoseVel.msg"
)
1. find_package(rosidl_default_generators REQUIRED)
find_package(rosidl_default_generators REQUIRED)
의미
rosidl_default_generators 패키지를 찾겠다는 뜻입니다.
이 패키지는 ROS 2의 .msg, .srv, .action 파일을 실제 코드로 변환해 주는 생성기들을 포함합니다.
예를 들어 .msg 파일 하나를 만들면 ROS 2는 내부적으로 다음과 같은 파일들을 자동 생성합니다.
C++ 메시지 헤더
Python 메시지 모듈
타입 서포트 코드
DDS 통신용 변환 코드
인트로스펙션 코드
REQUIRED 의미
REQUIRED
는 반드시 필요하다는 뜻입니다.
만약 rosidl_default_generators를 찾지 못하면 CMake 설정 단계에서 바로 에러가 납니다.
예:
Could not find a package configuration file provided by "rosidl_default_generators"
이 경우 보통 package.xml에 의존성이 빠졌거나 ROS 2 환경이 제대로 source 되지 않은 상태입니다.
2. rosidl_generate_interfaces(...)
rosidl_generate_interfaces(${PROJECT_NAME}
"msg/CmdAndPoseVel.msg"
)
의미
이 명령은 ROS 2 인터페이스 파일을 코드로 생성합니다.
여기서 인터페이스란 다음 세 가지를 말합니다.
.msg 메시지
.srv 서비스
.action 액션
현재 코드는 .msg 파일만 생성 대상으로 지정하고 있습니다.
3. ${PROJECT_NAME} 의미
${PROJECT_NAME}
는 CMake에서 현재 패키지 이름을 의미합니다.
보통 CMakeLists.txt 위쪽에 이런 코드가 있습니다.
project(my_robot_msgs)
그러면
${PROJECT_NAME}
는 자동으로
my_robot_msgs
가 됩니다.
따라서 아래 코드는
rosidl_generate_interfaces(${PROJECT_NAME}
"msg/CmdAndPoseVel.msg"
)
실제로는 이런 의미입니다.
rosidl_generate_interfaces(my_robot_msgs
"msg/CmdAndPoseVel.msg"
)
즉, my_robot_msgs라는 패키지 안에 있는 CmdAndPoseVel.msg 메시지를 생성하겠다는 뜻입니다.
4. "msg/CmdAndPoseVel.msg" 의미
"msg/CmdAndPoseVel.msg"
는 현재 패키지 폴더 기준으로 메시지 파일의 위치를 가리킵니다.
패키지 구조는 보통 이렇게 됩니다.
my_robot_msgs/
├── CMakeLists.txt
├── package.xml
└── msg/
└── CmdAndPoseVel.msg
CmdAndPoseVel.msg 파일 안에는 예를 들어 이런 내용이 들어갈 수 있습니다.
float64 cmd_vel
geometry_msgs/Pose pose
geometry_msgs/Twist velocity
또는
std_msgs/Header header
float64 x
float64 y
float64 z
float64 vx
float64 vy
float64 vz
이 .msg 파일을 기준으로 ROS 2가 자동으로 메시지 클래스를 생성합니다.
5. 실제 빌드 시 생성되는 것
예를 들어 패키지 이름이 my_robot_msgs이고 메시지 파일이 CmdAndPoseVel.msg라면, 빌드 후 대략 이런 파일들이 생성됩니다.
C++용
install/my_robot_msgs/include/my_robot_msgs/my_robot_msgs/msg/cmd_and_pose_vel.hpp
C++에서는 파일명이 보통 CamelCase → snake_case로 변환됩니다.
CmdAndPoseVel.msg
→ cmd_and_pose_vel.hpp
그래서 include는 보통 이렇게 합니다.
#include "my_robot_msgs/msg/cmd_and_pose_vel.hpp"
메시지 타입은 이렇게 사용합니다.
my_robot_msgs::msg::CmdAndPoseVel msg;
Python용
Python에서는 다음처럼 import합니다.
from my_robot_msgs.msg import CmdAndPoseVel
사용 예:
msg = CmdAndPoseVel()
전체 구조는 대략 아래와 같이 정리할 수 있습니다.
cmake_minimum_required(VERSION 3.8)
project(my_first_package_msgs)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
# find dependencies
find_package(ament_cmake REQUIRED)
# uncomment the following section in order to fill in
# further dependencies manually.
# find_package(<dependency> REQUIRED)
find_package(rosidl_default_generators REQUIRED)
rosidl_generate_interfaces(${PROJECT_NAME}
"msg/CmdAndPoseVel.msg"
)
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
# comment the line when a copyright and license is added to all source files
set(ament_cmake_copyright_FOUND TRUE)
# the following line skips cpplint (only works in a git repo)
# comment the line when this package is in a git repo and when
# a copyright and license is added to all source files
set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()
ament_package()

여기서 처음에 만들어진 불필요한 소스를 제거하면 아래와 같습니다.
cmake_minimum_required(VERSION 3.8)
project(my_first_package_msgs)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
find_package(ament_cmake REQUIRED)
find_package(rosidl_default_generators REQUIRED)
rosidl_generate_interfaces(${PROJECT_NAME}
"msg/CmdAndPoseVel.msg"
)
ament_package()

rosidl_generate_interfaces()는 ROS 2에서 .msg 파일을 실제 Python/C++ 코드에서 import 가능한 형태로 변환해 주는 역할을 합니다.
5. package.xml 설정
다음으로 package.xml에 메시지 생성과 실행에 필요한 의존성을 추가합니다.
<build_depend>rosidl_default_generators</build_depend>
<exec_depend>rosidl_default_runtime</exec_depend>
<member_of_group>rosidl_interface_packages</member_of_group>
CMakeLists.txt에만 아래 코드를 넣으면 부족합니다.
find_package(rosidl_default_generators REQUIRED)
package.xml에도 관련 의존성을 넣어야 합니다.
일반적으로 메시지 전용 패키지라면 다음처럼 작성합니다.
<buildtool_depend>ament_cmake</buildtool_depend>
<build_depend>rosidl_default_generators</build_depend>
<exec_depend>rosidl_default_runtime</exec_depend>
<member_of_group>rosidl_interface_packages</member_of_group>
<export>
<build_type>ament_cmake</build_type>
</export>
중요한 부분은 이것입니다.
<build_depend>rosidl_default_generators</build_depend>
빌드할 때 메시지 생성기가 필요하다는 뜻입니다.
<exec_depend>rosidl_default_runtime</exec_depend>
실행 시 생성된 메시지 타입을 사용하기 위해 필요합니다.
<member_of_group>rosidl_interface_packages</member_of_group>
이 패키지가 ROS 2 인터페이스 패키지라는 것을 알려줍니다.
그리고 이전 ROS 2 패키지 문제에서 자주 빠지는 항목이 이것입니다.
<export>
<build_type>ament_cmake</build_type>
</export>
이게 빠지면 colcon build나 패키지 인식 과정에서 문제가 생길 수 있습니다.

package.xml의 핵심은 다음 세 가지입니다.
<build_depend>rosidl_default_generators</build_depend>
빌드 시 메시지 코드를 생성하기 위해 필요합니다.
<exec_depend>rosidl_default_runtime</exec_depend>
실행 시 생성된 메시지 타입을 사용할 수 있게 해 줍니다.
<member_of_group>rosidl_interface_packages</member_of_group>
이 패키지가 ROS 2 인터페이스 패키지라는 것을 명시합니다.
6. 메시지 패키지 빌드
워크스페이스 루트로 이동합니다.
cd ~/ros2_study

워크스페이스 전체 빌드를 실행합니다.
colcon build


만약 메시지 패키지만 빌드할 경우에는 아래의 명령을 사용합니다.
colcon build --packages-select my_first_package_msgs
빌드가 끝났다면 환경을 다시 적용합니다.
source install/local_setup.bash
또는
sl

7. 메시지 타입 확인
새로 만든 메시지가 정상 등록되었는지 확인합니다.
ros2 interface show my_first_package_msgs/msg/CmdAndPoseVel
정상이라면 아래와 비슷하게 출력됩니다.

여기까지 되면 사용자 정의 메시지 생성은 성공입니다.
8. 두 개의 토픽을 구독하고 하나의 메시지로 묶기
이제 Python 노드에서 두 토픽을 구독해 보겠습니다.
목표는 다음과 같습니다.
- /turtle1/pose 구독
- /turtle1/cmd_vel 구독
- 두 토픽에서 들어온 데이터를 CmdAndPoseVel 메시지 객체에 저장
- 저장된 값을 출력
기존 Python 패키지로 이동합니다.
cd ~/ros2_study/src/my_first_package/my_first_package

새 파일을 생성합니다.
touch turtle_cmd_and_pose.py


[ touch 명령어 ]
- 빈 파일 생성: 존재하지 않는 파일명을 touch 명령어로 실행하면 내용이 없는 0바이트(byte) 파일이 새로 생성됩니다.
touch filename
- 시간 갱신: 이미 존재하는 파일에 touch를 사용하면 해당 파일의 접근 시간(Access Time)과 수정 시간(Modification Time)을 현재 서버 시간으로 업데이트합니다.
- 여러 파일 생성: 공백으로 구분하여 여러 파일을 동시에 생성할 수 있습니다.
touch file1.txt file2.txt
- 옵션:
-c (no-create): 파일이 없으면 새로 생성하지 않습니다.
-t [[CC]YY]MMDDhhmm[.ss]: 현재 시간이 아닌 지정된 시간으로 파일 타임스탬프를 설정합니다.
9. setup.py에 실행 노드 등록
my_first_package/setup.py 파일의 entry_points 항목에 새 노드를 추가합니다.
entry_points={
'console_scripts': [
'my_first_node = my_first_package.my_first_node:main',
'my_publisher = my_first_package.my_publisher:main',
'my_subscriber = my_first_package.my_subscriber:main',
'turtle_cmd_and_pose = my_first_package.turtle_cmd_and_pose:main',
],
},

이 설정을 해야 다음 명령으로 노드를 실행할 수 있습니다.
ros2 run my_first_package turtle_cmd_and_pose
10. pose 토픽 구독하기
turtlesim의 /turtle1/pose 토픽은 turtlesim.msg.Pose 타입을 사용합니다.
가장 기본적인 구독 코드는 다음과 같습니다. touch 명령으로 생성한 turtle_cmd_and_pose.py에 아래의 코드 내용을 입력하고 Ctrl+s로 저장합니다.
import rclpy as rp
from rclpy.node import Node
from turtlesim.msg import Pose
class CmdAndPose(Node):
def __init__(self):
super().__init__('turtle_cmd_pose')
self.sub_pose = self.create_subscription(
Pose,
'/turtle1/pose',
self.callback_pose,
10
)
def callback_pose(self, msg):
print(msg)
def main(args=None):
rp.init(args=args)
turtle_cmd_pose_node = CmdAndPose()
rp.spin(turtle_cmd_pose_node)
turtle_cmd_pose_node.destroy_node()
rp.shutdown()
if __name__ == '__main__':
main()
소스 편집이 완료되면 워크스페이스로 이동하여 다시 빌드를 수행합니다.
cd ~/ros2_study
colcon build
source install/local_setup.bash
또는
sl


새로운 터미널을 실행하여 turtlesim 노드를 실행합니다.
ros2 run turtlesim turtlesim_node

위에서 정의한 사용자 노드를 실행합니다.
ros2 run my_first_package turtle_cmd_and_pose

위의 결과를 보면 pose 토픽 구독 결과가 잘 출력되고 있음을 확인할 수 있습니다.
ctrl+c를 입력하여 노드를 종료합니다.

11. 사용자 정의 메시지 CmdAndPoseVel 사용하기
이제 직접 만든 메시지를 import 합니다.
from my_first_package_msgs.msg import CmdAndPoseVel

그리고 클래스 내부에서 메시지 객체를 하나 생성합니다.
self.cmd_pose = CmdAndPoseVel()

다음은 /turtle1/pose의 토픽을 받아 처리하는 기존의 callback_psoe() 함수를 아래와 같이 정의합니다. print(msg)는 삭제합니다. turtlesim1의 pose 토픽에서 CmdAndPoseVel 메시지에서 정의한 값만 사용합니다. 마지막 print() 문은 출력결과 확인용입니다.
def callback_pose(self, msg):
self.cmd_pose.pose_x = msg.x
self.cmd_pose.pose_y = msg.y
self.cmd_pose.linear_vel = msg.linear_velocity
self.cmd_pose.angular_vel = msg.angular_velocity
print(self.cmd_pose)

워크스페이스에서 빌드를 다시 실행합니다.

그리고 아래의 명령으로 노드를 다시 실행하여 수정한 소스가 정상적으로 실행되는지 확인합니다.
ros2 run my_first_package turtle_cmd_and_pose

위의 결과에서 확인할 수 있듯이 turtlesim pose의 토픽 일부가 cmd_pose에 잘 저장되는 것을 확인할 수 있습니다.
12. cmd_vel 토픽도 함께 구독하기
turtlesim에서 거북이를 움직이는 속도 명령은 /turtle1/cmd_vel 토픽으로 입력됩니다.
이 토픽의 타입은 geometry_msgs.msg.Twist입니다.
따라서 Twist를 import 해야 합니다.
from geometry_msgs.msg import Twist

그리고 __init__() 안에 두 번째 구독자를 생성합니다.
self.sub_cmdvel = self.create_subscription(
Twist,
'/turtle1/cmd_vel',
self.callback_cmd,
10
)

callback_cmd() 콜백 함수는 다음과 같이 작성합니다.
def callback_cmd(self, msg):
self.cmd_pose.cmd_vel_linear = msg.linear.x
self.cmd_pose.cmd_vel_angular = msg.angular.z
print(self.cmd_pose)
여기서 linear.x는 전진 속도, angular.z는 회전 속도입니다.
turtlesim은 2D 평면에서 움직이므로 주로 이 두 값을 사용합니다.

워크스페이스로 이동하여 빌드를 수행합니다.

이미 turtlesim 노드는 실행한 상태에서 거북이를 조종할 수 있는 turtle_teleop_key 노드를 실행합니다.

새롭게 수정한 turtle_cmd_and_pose 노드를 실행합니다.

이 상태에서 방향키를 이용하여 거북이를 조정하면 수정된 선형 속도 값이 변화된 것을 확인할 수 있습니다.

rqt_graph를 실행하여 토픽의 흐름을 확인합니다.

13. 최종 Python 코드
최종 코드는 다음과 같습니다.
import rclpy as rp
from rclpy.node import Node
from turtlesim.msg import Pose
from geometry_msgs.msg import Twist
from my_first_package_msgs.msg import CmdAndPoseVel
class CmdAndPose(Node):
def __init__(self):
super().__init__('turtle_cmd_pose')
self.sub_pose = self.create_subscription(
Pose,
'/turtle1/pose',
self.callback_pose,
10
)
self.sub_cmdvel = self.create_subscription(
Twist,
'/turtle1/cmd_vel',
self.callback_cmd,
10
)
self.cmd_pose = CmdAndPoseVel()
def callback_pose(self, msg):
self.cmd_pose.pose_x = msg.x
self.cmd_pose.pose_y = msg.y
self.cmd_pose.linear_vel = msg.linear_velocity
self.cmd_pose.angular_vel = msg.angular_velocity
print(self.cmd_pose)
def callback_cmd(self, msg):
self.cmd_pose.cmd_vel_linear = msg.linear.x
self.cmd_pose.cmd_vel_angular = msg.angular.z
print(self.cmd_pose)
def main(args=None):
rp.init(args=args)
turtle_cmd_pose_node = CmdAndPose()
rp.spin(turtle_cmd_pose_node)
turtle_cmd_pose_node.destroy_node()
rp.shutdown()
if __name__ == '__main__':
main()
14. 특정 패키지만 다시 빌드하기
Python 코드를 수정했으므로 다시 빌드해야 합니다.
전체 워크스페이스를 빌드해도 되지만, 시간이 오래 걸릴 수 있습니다.
이럴 때는 수정한 패키지만 빌드하는 것이 좋습니다.
cd ~/ros2_study
colcon build --packages-select my_first_package

빌드 후 환경을 다시 적용합니다.
source install/local_setup.bash
또는
sl

15. 최종 소스 실행 순서
터미널을 여러 개 열고 각각 다음 명령을 실행합니다.
터미널 1: turtlesim 실행
ros2 run turtlesim turtlesim_node
터미널 2: 사용자 노드 실행
ros2 run my_first_package turtle_cmd_and_pose
터미널 3: 거북이 조작 노드 실행
기존의 만든 my_publisher 노드를 사용할 경우 아래의 명령어를 실행합니다.
ros2 run my_first_package my_publisher
키보드 조작을 사용하려면 다음 명령도 가능합니다.
ros2 run turtlesim turtle_teleop_key
16. 실행 결과 이해하기
정상적으로 실행되면 turtle_cmd_and_pose 노드가 다음과 비슷한 데이터를 출력합니다.
my_first_package_msgs.msg.CmdAndPoseVel(
cmd_vel_linear=2.0,
cmd_vel_angular=0.0,
pose_x=5.54,
pose_y=5.54,
linear_vel=0.0,
angular_vel=0.0
)
이 출력은 두 종류의 데이터를 하나의 메시지 객체에 저장했다는 의미입니다.
- /turtle1/pose → 현재 위치와 실제 이동 속도
- /turtle1/cmd_vel → 명령으로 전달된 선속도와 각속도
- CmdAndPoseVel → 위 두 데이터를 하나로 모은 사용자 정의 메시지
실제 로봇 개발에서는 이런 방식이 많이 사용됩니다. 예를 들어 드론에서는 GPS, IMU, 속도 명령, 상태 플래그를 하나의 커스텀 메시지로 묶어 로깅하거나 다른 노드로 전달할 수 있습니다.
17. 왜 메시지 패키지를 분리하는 것이 좋은가요?
작은 예제에서는 Python 패키지 안에 모든 것을 넣고 싶을 수 있습니다. 하지만 프로젝트가 커지면 메시지 정의는 별도 패키지로 분리하는 것이 좋습니다.
이유는 다음과 같습니다.
첫째, 여러 패키지에서 같은 메시지를 재사용할 수 있습니다.
예를 들어 로봇 제어 패키지, 모니터링 패키지, 기록 패키지가 모두 같은 메시지를 사용할 수 있습니다.
둘째, 의존성 관리가 명확해집니다.
메시지만 필요한 패키지가 불필요하게 로봇 제어 코드 전체를 의존하지 않아도 됩니다.
셋째, 협업이 쉬워집니다.
하드웨어 담당자는 메시지 규격만 보고 데이터를 발행할 수 있고, 소프트웨어 담당자는 같은 메시지를 구독해서 알고리즘을 개발할 수 있습니다.
18. 자주 발생하는 오류
a. 메시지가 인식되지 않는 경우
ros2 interface show my_first_package_msgs/msg/CmdAndPoseVel
위 명령에서 메시지가 나오지 않는다면 아래를 확인해야 합니다.
- msg/CmdAndPoseVel.msg 파일 이름이 정확한지
- CMakeLists.txt에 rosidl_generate_interfaces()가 있는지
- package.xml에 rosidl_default_generators가 있는지
- 빌드 후 source install/local_setup.bash를 했는지
b. Python에서 import가 안 되는 경우
from my_first_package_msgs.msg import CmdAndPoseVel
이 부분에서 오류가 난다면 대부분 빌드 또는 source 문제입니다.
해결 순서는 다음과 같습니다.
cd ~/ros2_study
colcon build
source install/local_setup.bash
그래도 안 되면 기존 빌드 결과를 지우고 다시 빌드합니다.
rm -rf build install log
colcon build
source install/local_setup.bash
c. setup.py에 entry point를 추가하지 않은 경우
Python 파일을 만들었더라도 setup.py에 등록하지 않으면 ros2 run으로 실행할 수 없습니다.
반드시 아래처럼 등록해야 합니다.
'turtle_cmd_and_pose = my_first_package.turtle_cmd_and_pose:main',
19. 정리
이번 예제에서는 ROS 2에서 사용자 정의 메시지를 만들고, 두 개의 토픽 데이터를 하나의 메시지 객체에 저장하는 방법을 살펴보았습니다.
핵심 흐름은 다음과 같습니다.
my_first_package_msgs 패키지 생성
→ msg/CmdAndPoseVel.msg 작성
→ CMakeLists.txt 수정
→ package.xml 수정
→ colcon build
→ ros2 interface show로 확인
→ Python 노드에서 import
→ pose와 cmd_vel 토픽 구독
→ 하나의 CmdAndPoseVel 객체에 저장
이 구조는 단순한 예제에만 쓰이는 방식이 아닙니다.
실제 로봇, 드론, 자율주행 시스템에서도 센서 데이터와 제어 명령을 하나의 명확한 데이터 구조로 묶을 때 자주 사용하는 방식입니다.
ROS 2를 제대로 사용하려면 사용자 정의 메시지 작성은 반드시 익숙해져야 하는 핵심 기능입니다.
'강좌 > ROS2' 카테고리의 다른 글
| 토픽, 서비스, 액션 정리 (0) | 2026.05.19 |
|---|---|
| ROS2 사용자 정의 메세지 만들기 #2 (0) | 2026.05.09 |
| ROS2 패키지 만들고 토픽 다루기 (0) | 2026.05.08 |
| ROS 2 Python Service Client 사용하기 (0) | 2026.05.08 |
| Python에서 ROS2 토픽 발행 (0) | 2026.05.07 |
