이번 글에서는 파이썬으로 피보나치 수를 출력하는 액션을 만들어보겠습니다.
액션(action)은 토픽(topic)과 서비스(service)가 혼합된 형태의 통신방식입니다. 액션 클라이언트(client)가 서비스를 통해 목표(goal)를 설정하면 액션 서버(server)는 결과(result)에 도달할때까지 토픽을 통해 피드백(feedback)을 보냅니다.
액션 인터페이스부터 만들어 보겠습니다. 지난번 글에 작성한 tutorial_interfaces 패키지에 액션 인터페이스를 추가하겠습니다. 인터페이스 이름은 Fibonacci로 하겠습니다. $ mkdir ~/dev_ws/src/tutorial_interfaces/action $ touch ~/dev_ws/src/tutorial_interfaces/action/Fibonacci.action |
빌드 설정파일 CMakeLists.txt를 수정합니다. rosidl_generate_interfaces에 액션 인터페이스를 추가하고 저장하세요.
액션 인터페이스를 작성하겠습니다.
빌드해주세요. $ cd ~/dev_ws && colcon build --symlink-install --packages-select tutorial_interfaces |
피보나치 액션 패키지를 만들겠습니다. 패키지 이름은 fibonacci_action_py로 하고 의존성 패키지로 rclpy와 tutorial_interfaces를 추가합니다. $ cd ~/dev_ws/src && ros2 pkg create fibonacci_action_py --build-type ament_python --dependencies rclpy tutorial_interfaces |
package.xml 파일을 열어 version, description, maintainer, license를 수정하고 저장합니다.
setup.py 파일을 열고 파이썬 패키지 빌드 설정을 합니다. entry_points 에는 server 노드와 client 노드에 대한 스크립트를 설정합니다.
서버 노드와 클라이언트 노드를 생성합니다. $ touch ~/dev_ws/src/fibonacci_action_py/fibonacci_action_py/{server.py,client.py} |
서버 노드부터 작성하겠습니다.
rclpy 모듈과 ActionServer, Node 모듈 및 Fibonacci 모듈을 import합니다. time 모듈도 import 합니다.
import time
import rclpy from rclpy.action import ActionServer from rclpy.node import Node
from tutorial_interfaces.action import Fibonacci |
서버 노드 클래스를 작성합니다. 클래스 이름은 Server이고, Node 클래스를 상속합니다.
Server 클래스 생성자를 작성합니다. super 함수를 통해 부모 클래스인 Node 클래스의 생성자에 노드 이름을 매개변수로 작성합니다. 노드 이름은 'server' 입니다.
def __init__(self): super().__init__('server') |
ActionServer 함수로 서버를 생성합니다. 매개변수로 실행 노드, 메시지 타입, 액션 이름, 콜백 함수를 넘겨줍니다.
self._action_server = ActionServer( self, Fibonacci, 'action', self.callback) |
콜백함수를 정의합니다. 콜백함수가 호출되면 로그를 남깁니다. 콜백함수는 액션 처리 객체(goal_handle)을 매개변수로 받도록 작성합니다.
def callback(self, goal_handle): self.get_logger().info('Executing goal...') |
피드백 메시지를 작성합시다. 피드백 메시지에는 피보나치 수의 배열이 입력됩니다. 액션 목표에 도달할때까지 액션 처리 객체의 publish_feedback 함수를 통해 피드백 메시지를 발행합니다.
feedback_msg = Fibonacci.Feedback() feedback_msg.partial_sequence = [0, 1]
for i in range(1, goal_handle.request.order): feedback_msg.partial_sequence.append( feedback_msg.partial_sequence[i] + feedback_msg.partial_sequence[i-1]) self.get_logger().info('Feedback: {0}'.format(feedback_msg.partial_sequence)) goal.handle.publish_feedback(feedback_msg) time.sleep(1) |
액션 목표에 도달하면 액션 처리 객체의 succeed 함수를 통해 클라이언트에 액션 상태가 변했음을 알리고 결과 메시지를 리턴합니다.
goal_handle.succeed()
result = Fibonacci.Result() result.sequence = feedback_msg.partial_sequence
return result |
메인함수를 작성합니다. 액션 서버 노드를 만들고 spin 함수를 통해 서버를 회전시킵니다.
def main(args=None): rclpy.init(args=args)
server = Server()
rclpy.spin(server) |
클라이언트 노드를 작성합니다.
rclpy 모듈과 tutorial_interfaces 모듈을 import 합니다.
import rclpy from rclpy.action import ActionClient from rclpy.node import Node
from tutorial_interfaces.action import Fibonacci |
클라이언트 노드 클래스를 작성합니다. 클래스 이름은 Client이고, Node 클래스를 상속합니다.
Client 클래스 생성자를 작성합니다. super 함수를 통해 부모 클래스인 Node 클래스의 생성자에 노드 이름을 매개변수로 작성합니다. 노드 이름은 'client' 입니다. def __init__(self): super().__init__('client') |
ActionClient 함수로 클라이언트를 생성합니다. 매개변수로 실행 노드, 메시지 타입, 액션 이름을 넘겨줍니다.
self._action_client = ActionClient(self, Fibonacci, 'action') |
목표 설정 함수를 정의합니다. 클라이언트의 wait_for_server 함수를 통해 서버를 확인하고 send_goal_async 함수를 통해 목표 메시지를 서버에 보냅니다. 매개변수로 목표 메시지, 피드백 콜백 함수를 넘겨줍니다. add_done_callback 함수를 통해 결과의 응답 메시지 콜백 함수를 추가해줍니다.
def send_goal(self, order): goal_msg = Fibonacci.Goal() goal_msg.order = order
self._action_client.wait_for_server()
self._send_goal_future = self._action_client.send_goal_async( goal_msg, feedback_callback=self.feedback_callbak)
self._send_goal_future.add_done_callback(self.goal_response_callback) |
결과 메시지 콜백 함수를 정의합니다. 액션 상태를 확인 후 로그를 출력합니다.
def goal_response_callback(self, future): goal_handle = future.result() if not goal_handle.accepted: self.get_logger().info('Goal rejected :(') return
self.get_logger().info('Goal accepted :)')
self._get_result_future = goal_handle.get_result_async() self._get_result_future.add_done_callback(self.get_result_callback)
def get_result_callback(self, future): result = future.result().result self.get_logger().info('Result: {0}'.format(result.sequence)) rclpy.shutdown() |
피드백 콜백 함수를 정의합니다.
def feedback_callback(self, feedback_msg): feedback = feedback_msg.feedback self.get_logger().info('Received feedback: {0}'.format(feedback.partial_sequence)) |
메인함수를 작성합니다. 액션 클라이언트 노드를 만들고 서버에 목표 메시지를 보냅니다. spin 함수를 통해 서버를 회전시킵니다. def main(args=None): rclpy.init(args=args)
client = Client()
client.send_goal(10)
rclpy.spin(client) |
colcon으로 패키지를 빌드해주세요.
$ cd ~/dev_ws && colcon build --symlink-install --packages-select fibonacci_action_py |
서버를 실행합니다. $ overlay && ros2 run fibonacci_action_py server |
터미널을 새로 열고 클라이언트를 실행합니다. $ overlay && ros2 run fibonacci_action_py client |
다음과 같이 order가 목표값인 10이 될때까지 피보나치 수열을 반복해서 더하고 피드백을 출력합니다. 목표값인 10에 이르면 결과값을 출력하고 클라이언트 노드가 종료됩니다.
클라이언트를 실행하지 않고 다음과 같이 CLI 명령어를 통해 액션을 수행할 수도 있습니다. $ overlay && ros2 action send_goal action tutorial_interfaces/action/Fibonacci --feedback "{order: 15}" |
|