이번 글에서는 앞에서 만든 사용자 정의 메시지 CmdAndPoseVel을 실제 토픽으로 발행하고, 이어서 사용자 정의 서비스 MultiSpawn.srv까지 만들어 보겠습니다.
핵심 목표는 다음과 같습니다.
1. /turtle1/pose 토픽 구독
2. /turtle1/cmd_vel 토픽 구독
3. 두 토픽 데이터를 CmdAndPoseVel 메시지에 저장
4. /cmd_and_pose 토픽으로 통합 데이터 발행
5. rqt_graph로 노드와 토픽 연결 확인
6. MultiSpawn.srv 서비스 정의 생성
7. 서비스 서버 생성
8. 서비스 클라이언트 개념 확장
1. 두 토픽 데이터를 하나의 토픽으로 다시 발행하기
앞에서는 /turtle1/pose와 /turtle1/cmd_vel을 각각 구독한 뒤, 두 데이터를 하나의 CmdAndPoseVel 객체에 저장했습니다.
이제는 저장만 하는 것이 아니라, 이 데이터를 새로운 토픽으로 발행하겠습니다.
새로 발행할 토픽 이름은 다음과 같습니다.
/cmd_and_pose
이 토픽은 우리가 직접 만든 메시지 타입을 사용합니다.
from my_first_package_msgs.msg import CmdAndPoseVel
a. Publisher 추가하기
turtle_cmd_and_pose.py 파일의 클래스 내부에서 publisher를 생성합니다.
self.publisher = self.create_publisher(
CmdAndPoseVel,
'/cmd_and_pose',
10
)

여기서 각 인자의 의미는 다음과 같습니다.
CmdAndPoseVel → 발행할 메시지 타입
/cmd_and_pose → 발행할 토픽 이름
10 → QoS queue size
즉, 이 노드는 /turtle1/pose와 /turtle1/cmd_vel을 구독하면서 동시에 /cmd_and_pose라는 새 토픽을 발행하는 구조가 됩니다.
b. Timer 추가하기
토픽을 계속 발행하려면 일정 주기로 publish를 호출해야 합니다.
self.timer_period = 1.0
self.timer = self.create_timer(
self.timer_period,
self.timer_callback
)

self.timer_period = 1.0은 1초마다 콜백 함수를 실행한다는 의미입니다.
타이머 콜백은 다음과 같이 작성합니다.
def timer_callback(self):
self.publisher.publish(self.cmd_pose)

이제 self.cmd_pose에 저장된 최신 pose 값과 cmd_vel 값이 1초마다 /cmd_and_pose 토픽으로 발행됩니다.
2. 최종 turtle_cmd_and_pose.py 코드
아래는 두 개의 토픽을 구독하고, 하나의 사용자 정의 메시지로 다시 발행하는 최종 코드입니다.
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.timer_period = 1.0
self.publisher = self.create_publisher(
CmdAndPoseVel,
'/cmd_and_pose',
10
)
self.timer = self.create_timer(
self.timer_period,
self.timer_callback
)
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
def callback_cmd(self, msg):
self.cmd_pose.cmd_vel_linear = msg.linear.x
self.cmd_pose.cmd_vel_angular = msg.angular.z
def timer_callback(self):
self.publisher.publish(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()
3. 빌드하기
Python 코드를 수정했으므로 다시 빌드합니다.
cd ~/ros2_study
colcon build --packages-select my_first_package

빌드 후에는 반드시 환경을 다시 불러옵니다.
source install/local_setup.bash
또는
sl

4. 실행 순서
터미널을 4개 준비합니다.
터미널 1: turtlesim 실행
ros2 run turtlesim turtlesim_node

터미널 2: 기존 publisher 실행
ros2 run my_first_package my_publisher


터미널 3: 통합 노드 실행
ros2 run my_first_package turtle_cmd_and_pose

이 노드는 다음 역할을 합니다.
/turtle1/pose 구독
/turtle1/cmd_vel 구독
/cmd_and_pose 발행
터미널 4: rqt_graph 실행
rqt_graph


5. rqt_graph로 토픽 흐름 확인하기
rqt_graph를 실행하면 노드와 토픽의 연결 관계를 그래프로 볼 수 있습니다.
구조는 대략 다음과 같습니다.
turtlesim_publisher
↓
/turtle1/cmd_vel
↓
turtlesim
↓
/turtle1/pose
↓
turtle_cmd_pose
↓
/cmd_and_pose
여기서 중요한 점은 turtle_cmd_pose 노드가 단순 구독자가 아니라는 것입니다.
이 노드는 두 개의 입력 토픽을 받아서 하나의 사용자 정의 토픽으로 다시 발행하는 중간 처리 노드입니다. 실제 로봇 시스템에서는 이런 형태가 매우 자주 사용됩니다.
예를 들면 다음과 같습니다.
GPS + IMU + 속도 명령 → 하나의 상태 메시지로 통합
카메라 + 라이다 + 엔코더 → 인식 노드용 통합 메시지 구성
드론 위치 + 속도 + 모드 정보 → 관제 시스템용 상태 토픽 발행
6. topic echo로 발행 데이터 확인하기
/cmd_and_pose 토픽이 실제로 발행되는지 확인하려면 다음 명령을 사용합니다.
ros2 topic echo /cmd_and_pose
정상적으로 동작하면 다음과 비슷한 값이 출력됩니다.

이 출력이 보이면 사용자 정의 메시지가 토픽으로 정상 발행되고 있는 것입니다.
'강좌 > ROS2' 카테고리의 다른 글
| 서비스 정의 만들기 (0) | 2026.05.21 |
|---|---|
| 토픽, 서비스, 액션 정리 (0) | 2026.05.19 |
| ROS2 사용자 정의 메세지 만들기 #1 (0) | 2026.05.09 |
| ROS2 패키지 만들고 토픽 다루기 (0) | 2026.05.08 |
| ROS 2 Python Service Client 사용하기 (0) | 2026.05.08 |
