이번 시간에는 우리가 ROS2 기본 학습에서 배웠던 Turtlesim의 geometry_msgs/twist 메시지를 이용하여 거북이를 움직여 원을 그리도록 하는 노드를 만들어 보겠습니다.
turtlesim의 거북이를 움직이기 위해 우리는 아래와 같이 turtlesim 노드의 /turtle1/cmd_vel 토픽을 이용할 것입니다.
draw_circle.py
my_robot_controller 패키지의 src 디렉토리 아래에 my_robot_controller 노드 디렉토리로 이동하여 새로운 ROS 프로그램인 draw_circle.py 파일을 만들고 실행 권한을 부여 합니다.
Copy cd ~/ros2_ws/src/my_robot_controller/my_robot_controller
touch draw_circle.py
chmod +x draw_circle.py
이제 vscode를 이용하여 /turtlesim 노드에게 cmd_vel 토픽을 발행(publish)하는 코드를 작성해 보겠습니다.
Copy #!/usr/bin/env python3
import rclpy
from rclpy.node import Node
from geometry_msgs.msg import Twist
class DrawCirclenode(Node):
def __init__(self):
super().__init__("draw_circle")
self.cmd_vel_pub_ = self.create_publisher(Twist,"/turtle1/cmd_vel", 10)
self.timer_ = self.create_timer(0.5, self.send_velocity_command)
self.get_logger().info("Draw circle node has been started.")
def send_velocity_command(self):
msg = Twist()
msg.linear.x = 2.0
msg.angular.z = 1.0
self.cmd_vel_pub_.publish(msg)
def main(args=None):
rclpy.init(args=args)
node = DrawCirclenode()
rclpy.spin(node)
rclpy.shutdown()
코드 분석
우선 ROS2 패키지를 import 합니다.
Copy import rclpy
from rclpy.node import Node
from geometry_msgs.msg import Twist
cmd_vel 토픽을 사용하기 위해 cmd_vel 토픽의 데이터 타입을 알아야 합니다.
ros2 topic info 명령어를 이용하여 cmd_vel 토픽의 데이터 타입을 조회 합니다.
Copy ros2 topic info /turtle1/cmd_vel
Type: geometry_msgs/msg/Twist
Publisher count: 1
Subscription count: 1
우리는 cmd_vel 토픽의 데이터 타입이 geometry_msgs/msg/Twist 타입 이라는 것을 알 수 있습니다.
이 데이터 타입에 대한 정확한 내용을 보려면 ros2 interface show 명령을 사용 합니다.
Copy ros2 interface show geometry_msgs/msg/Twist
Vector3 linear
float64 x
float64 y
float64 z
Vector3 angular
float64 x
float64 y
float64 z
geometry_msgs/msg/Twist 타입은 안에 Vector3 타입의linear와 angular 구조체 데이터 타입을 가지고 있는 데이터 타입 이라는 것을 알 수 있습니다.
linear, angular 메시지 타입
main() 함수
Copy def main(args=None):
rclpy.init(args=args)
node = DrawCirclenode()
rclpy.spin(node)
rclpy.shutdown()
메인 함수는 일반적인 main() 함수 구조와 동일 합니다.
rclpy 패키지의 init 메쏘드를 이용하여 ROS 프로그램을 초기화 한 후, 노드를 생성하고 spin() 메쏘드를 이용하여 노드를 실행 시킵니다.
shutdown() 메쏘드는 노드 종료 시그널(Ctr+C)을 받았을때 노드를 메모리에서 해제합니다.
DrawCirclenode 클래스
Copy class DrawCirclenode(Node):
def __init__(self):
super().__init__("draw_circle")
self.cmd_vel_pub_ = self.create_publisher(Twist,"/turtle1/cmd_vel", 10)
self.timer_ = self.create_timer(0.5, self.send_velocity_command)
self.get_logger().info("Draw circle node has been started.")
def send_velocity_command(self):
msg = Twist()
msg.linear.x = 2.0
msg.angular.z = 1.0
self.cmd_vel_pub_.publish(msg)
노드를 초기화 합니다.
Copy super().__init__("draw_circle")
다음으로 /turtle1 노드에 cmd_vel 토픽을 발행할 퍼블리셔를 만들어 줍니다.
Copy self.cmd_vel_pub_ = self.create_publisher(Twist,"/turtle1/cmd_vel", 10)
create_publisher 메쏘드의 첫번째 인자는 데이터 타입 "Twist", 두번째 인자 "/turtle1/cmd_vel"는 토픽명, 세번째 인자 "10"은 토픽이 저장될 큐(Queue)의 사이즈 입니다.
다음으로 앞서 배운바와 같이 콜백 함수를 0.5초 마다 실행 시키는 콜백 타이머를 생성 하여 줍니다.
Copy self.timer_ = self.create_timer(0.5, self.send_velocity_command)
send_velocity_command라는 이름의 콜백 함수를 만들어 주고 앞서 만들어준 퍼블리셔인 cmd_vel_pub_ 인스턴스를 이용해 Twist 메세지를 발행하게 합니다.
Copy def send_velocity_command(self):
msg = Twist()
msg.linear.x = 2.0
msg.angular.z = 1.0
self.cmd_vel_pub_.publish(msg)
앞으로 linear.x(Forward) 만큼 전진 하면서 angular.z(Yaw) 만큼 회전하도록 데이터를 채워주고 마지막으로 publish 메쏘드를 이용해 토픽을 발행 합니다.
이제 코드가 완성 되었습니다.
package.xml 의존성(dependancy) 추가
빌드시 에러가 발생되지 않도록 새로운 데이터 타입인 Twist 메시지를 가지고 있는 geometry_msgs 패키지를 package.xml 파일에 추가해 줍니다. 또한, 우리는 기존의turtlesim 패키지를 이용할 것이므로 turtlesim 패키지도 같이 추가해 주어야 합니다.
Copy <depend>geometry_msgs</depend>
<depend>turtlesim</depend>
entry_point 추가
노드를 실행할 수 있도록 setup.py 파일을 수정해 줍니다.
Copy entry_points={
'console_scripts': [
"test_node = my_robot_controller.my_first_node:main",
"draw_circle = my_robot_controller.draw_circle:main"
],
},
빌드
이제 우리가 작성한 새로운 노드 DrawCirclenode 프로그램을 빌드해 봅시다.
Copy $ colcon build --symlink-install
Finished <<< my_robot_controller [1.09s]
Summary: 1 packages finished [1.26s]
에러 없이 빌드가 잘 수행 되었습니다.
실행
터미널에서 turtlesim 노드를 실행 합니다.
Copy $ ros2 run turtlesim turtlesim_node
새로운 터미널을 열고 draw_circle 노드를 실행 합니다.
Copy $ ros2 run my_robot_controller draw_circle
[INFO] [1687238495.075864724] [draw_circle]: Draw circle node has been started.
이제 거북이가 원을 그리며 회전 하는 것을 볼 수 있습니다.
rqt_graph를 이용하여 노드와 토픽의 구조를 살펴 봅니다.
/draw_circle 노드에서 /turtle1/cmd_vel 토픽을 발행하여 /turtlesim 노드가 subscribe(구독) 하는 것을 알 수 있습니다.