이 포스트는 이전 포스트에 이어서 ROS2의 Topic에 대한 간단한 설명입니다.
이 포스트는 다음 과정을 완료한 후에 참고하시길 바랍니다.
1. Topic
- Topic은 Node들 간에 정보를 주고받기 위한 필수 요소입니다.
- Topic은 N:N 통신방식으로 하나의 Node는 여러 개의 Topic을 발송할 수 있고, 여러 개의 Topic을 수신할 수 있습니다.
- Topic은 일방향 통신으로 Node가 Topic을 정상 수신했는지 여부 또는 정상 처리 했는지 여부 등을 관심을 두지 않습니다.
- 첫 번째 터미널에서 아래 명령을 실행해서 'turtlesim.launch.py'를 실행합니다.
$ cd ~/Workspace/ros_ws
$ source install/setup.bash
$ ros2 launch ros_tutorial turtlesim.launch.py
- 두 번째 터미널에서 아래 명령을 실행해서 '/turtle1/cmd_vel' Topic을 전송합니다. 아래 그림과 같이 주기적으로 Topic을 전송하는 것을 확인할 수 있습니다.
$ ros2 topic pub /turtle1/cmd_vel geometry_msgs/msg/Twist "{linear: {x: 2.0, y: 0.0, z: 0.0}, angular: {x: 0.0, y: 0.0, z: 1.8}}"
- Turtlesim 화면은 '/turtle1/cmd_vel'을 수신해서 그 명령에 따라서 TurtleBot이 원을 그리면서 도는 것을 확인할 수 있습니다.
- 두 번째 터미널에서 'Ctrl+C'를 눌러서 Topic 전송을 종료하면 TurtleBot이 회전을 멈추는 것을 확인할 수 있습니다.
- 아래 명령을 실행해서 Topic 목록을 확인합니다. 아래 그림과 같이 Topic 목록을 확인할 수 있습니다.
$ ros2 topic list
- 아래 명령을 실행해서 '/turtle1/cmd_vel'의 상세 정보를 확인합니다. 아래와 같은 정보를 확인할 수 있습니다.
◦ Type: Topic에서 주고받는 메시지 type입니다.
◦ Publisher count: Topic을 publish 하는 Node 숫자입니다.
◦ Subscription count: Topic을 subscribe 하는 Node 숫자입니다.
$ ros2 topic info /turtle1/cmd_vel
- 아래 명령을 실행해서 'geometry_msgs/msg/Twist'를 사용하는 모든 Topic을 찾을 수 있습니다.
$ ros2 topic find geometry_msgs/msg/Twist
- 아래 명령을 실행해서 'geometry_msgs/msg/Twist'의 상세정보를 확인할 수 있습니다. 아래 그림과 같이 방향을 의미하는 Vector3 형식의 linear 변수와 회전을 의미하는 Vector3 형식의 angular 값으로 구성된 것을 확인할 수 있습니다.
$ ros2 interface show geometry_msgs/msg/Twist
2. Topic - Publisher
- TurtleBot을 회전하도록 했던 '/turtle1/cmd_vel' Topic을 발송하는 Publisher를 python으로 구현해 보겠습니다.
- 'src/ros_tutorial/package.xml' 파일을 아래와 같이 수정합니다. 아래 그림과 같이 Publisher가 사용할 dependency를 추가했습니다.
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>ros_tutorial</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<maintainer email="cchyun@todo.todo">cchyun</maintainer>
<license>TODO: License declaration</license>
<depend>rclpy</depend>
<depend>geometry_msgs</depend>
<test_depend>ament_copyright</test_depend>
<test_depend>ament_flake8</test_depend>
<test_depend>ament_pep257</test_depend>
<test_depend>python3-pytest</test_depend>
<export>
<build_type>ament_python</build_type>
</export>
</package>
- 'src/ros_tutorial/setup.py'를 아래와 같이 수정합니다. 아래 그림과 같이 'turtlesim_circle'이라는 명령을 등록했습니다.
import os
from glob import glob
from setuptools import setup
package_name = 'ros_tutorial'
setup(
name=package_name,
version='0.0.0',
packages=[package_name],
data_files=[
('share/ament_index/resource_index/packages',
['resource/' + package_name]),
('share/' + package_name, ['package.xml']),
(os.path.join('share', package_name, 'launch'), glob('launch/*.launch.py')),
],
install_requires=['setuptools'],
zip_safe=True,
maintainer='cchyun',
maintainer_email='cchyun@todo.todo',
description='TODO: Package description',
license='TODO: License declaration',
tests_require=['pytest'],
entry_points={
'console_scripts': [
'turtlesim_circle = ros_tutorial.turtlesim_circle:main',
],
},
)
- 'src/ros_tutorial/ros_tutorial/turtlesim_circle.py' 파일을 만들고 아래와 같이 편집합니다. TurtleBot에 회전할 수 있도록 'geometry_msgs/msg/Twist' 메시지를 1초에 2번 보내는 코드입니다.
#!/usr/bin/env python3
import rclpy
from rclpy.node import Node
from geometry_msgs.msg import Twist, Vector3
class TurtlesimCirclePublisher(Node):
def __init__(self):
super().__init__('turtlesim_circle')
self.publisher = self.create_publisher(Twist, '/turtle1/cmd_vel', 10) # 10: quesize
self.timer = self.create_timer(0.5, self.timer_callback)
def timer_callback(self):
msg = Twist()
msg.linear = Vector3(x=2.0, y=.0, z=.0)
msg.angular = Vector3(x=.0, y=.0, z=1.8)
self.publisher.publish(msg)
def main(args=None):
rclpy.init(args=args)
publisher = TurtlesimCirclePublisher()
rclpy.spin(publisher) # blocked until ros2 shutdown
publisher.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
- 첫 번째 터미널에서 'Ctrl+c'를 여러 번 눌러서 프로그램을 종료 후 아래 명령을 실행해서 컴파일, 환경설정 그리고 'turtlesim.launch.py'를 실행합니다.
$ cd ~/Workspace/ros_ws
$ colcon build --symlink-install
$ source install/setup.bash
$ ros2 launch ros_tutorial turtlesim.launch.py
- 두 번째 터미널에서 아래 명령을 실행해서 'turtlesim_circle'을 실행합니다.
$ cd ~/Workspace/ros_ws
$ source install/setup.bash
$ ros2 run ros_tutorial turtlesim_circle
- TurtleBot이 이전에 'ros2 topic..' 명령을 실행할 때와 동일하게 회전하는 것을 확인할 수 있습니다.
- rqt_graph 창의 '새로고침' 버튼을 누르면 '/turtlesim_circle' Node에서 '/turtlesim' Node로 '/turtle1/cmd_vel' Topic을 발송하는 것을 확인할 수 있습니다.
- 세 번째 터미널에서 아래 명령을 실행해서 '/turtle1/cmd_vel' Topic을 수신해 봅니다. 아래 그림과 같이 '/turtle1/cmd_vel' Topic을 수신한 정보가 화면에 출력되는 것을 확인할 수 있습니다.
$ ros2 topic echo /turtle1/cmd_vel
3. Topic - Subscriber
- TurtleBot을 회전하도록 했던 '/turtle1/cmd_vel' Topic을 수신하는 Subscriber를 python으로 구현해 보겠습니다.
- 'src/ros_tutorial/setup.py' 파일의 'console_scripts' 부분에 아래 내용을 추가합니다.
'turtlesim_echo = ros_tutorial.turtlesim_echo:main',
- 'src/ros_tutorial/ros_tutorial/turtlesim_echo.py' 파일을 만들고 아래와같이 편집합니다.
#!/usr/bin/env python3
import rclpy
from rclpy.node import Node
from geometry_msgs.msg import Twist, Vector3
class TurtlesimCircleSubscriber(Node):
def __init__(self):
super().__init__('turtlesim_echo')
self.subscriber = self.create_subscription(Twist, '/turtle1/cmd_vel',
self.topic_callback, 10) # 10: quesize
def topic_callback(self, msg):
self.get_logger().info(f'recv mes: {msg}')
def main(args=None):
rclpy.init(args=args)
subscriber = TurtlesimCircleSubscriber()
rclpy.spin(subscriber) # blocked until ros2 shutdown
subscriber.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
- 첫 번째 터미널에서 아래 명령을 실행해서 컴파일, 환경설정 그리고 'turtlesim.launch.py'를 실행합니다.
$ cd ~/Workspace/ros_ws
$ colcon build --symlink-install
$ source install/setup.bash
$ ros2 launch ros_tutorial turtlesim.launch.py
- 두 번째 터미널에서 아래 명령을 실행해서 'turtlesim_circle'을 실행합니다.
$ cd ~/Workspace/ros_ws
$ source install/setup.bash
$ ros2 run ros_tutorial turtlesim_circle
- 세 번째 터미널에서 아래 명령을 실행해서 'turtlesim_echo'을 실행합니다.
$ cd ~/Workspace/ros_ws
$ source install/setup.bash
$ ros2 run ros_tutorial turtlesim_echo
- rqt_graph 창의 '새로고침' 버튼을 누르면 '/turtlesim_circle' Node에서 '/turtlesim' Node와 '/turtlesim_echo' Node로 '/turtle1/cmd_vel' Topic을 발송하는 것을 확인할 수 있습니다.
'로봇 > ROS' 카테고리의 다른 글
ROS2 Minimal Tutorial - Action (0) | 2023.07.14 |
---|---|
ROS2 Minimal Tutorial - Service (0) | 2023.07.14 |
ROS2 Minimal Tutorial - Basic (0) | 2023.07.13 |
Windows에서 Docker를 이용해 ROS2, Gazebo 설치하기 (7) | 2023.07.12 |
ROS1에 CygLiDAR 연동하기 (0) | 2023.01.19 |