이 블로그 시리즈에서는 Gazebo + ROS 2 + PX4(MAVROS)를 활용해 드론을 제어하고, 최적 제어 알고리즘 Model Predictive Path Integral (MPPI) 를 직접 구현하는 과정을 기록합니다. 이후에는 더 진화된 강화학습(RL) 기반 제어로까지 확장하며, 최신 오픈소스 생태계가 실제 연구·개발 파이프라인에서 어떻게 유기적으로 엮이는지 보여드릴 예정입니다.
시리즈 1·2 편에서 gazebo 시뮬레이터에서 px4를 연동방법하는 방법에 대해 알아보았습니다. 이번글에서는 PX4 Offboard모드를 통해 Gazebo 시뮬레이션 환경에서 드론을 이륙하는 과정까지 살펴보기로 합니다. 이번 글은 실기체로의 확장까지 염두에 두고 있기 때문에 Qgroundcontrol의 사용을 배제한 ROS2만으로 운영하는 구성을 목표로 합니다.
이번 글에서 다룰 내용은 다음과 같습니다.
- MAVROS를 통해 /mavros/setpoint_position/local 에 setpoint 명령 퍼블리시
- 드론을 arm 상태로 전환
- Offboard 모드로 변경
- 자동 이륙
1. Offboard 모드란?
PX4에서 외부 제어기(예: ROS2 노드)로부터 위치, 속도 등의 제어 명령을 받아 직접 비행하는 모드입니다. 이를 위해서는 일정 주기(20Hz 이상)로 setpoint 메시지를 지속적으로 보내야 합니다. 이는 PX4의 Failsafe로직 중 하나로 PX4는 “외부에서 꾸준히 명령이 들어오고 있다”는 확신이 있어야 Offboard 모드로 넘어갑니다.
정의 | PX4가 외부 컨트롤러(ROS2 노드)로부터 setpoint를 받아 직접 비행하는 모드 |
필수 조건 | 최소 20 Hz (0.05 s) 주기로 setpoint 스트림 유지 |
장점 | 위치·속도·가속도 등 모든 축을 실시간 제어—고급 경로·MPC·MPPI 알고리즘 적용 가능 |
2. 주요 통신 흐름
/mavros/setpoint_position/local ← 드론이 가야할 위치 결정
/mavros/state → 현재 모드·Arm 상태 확인
/mavros/cmd/arming ↔ Arm/Disarm 요청
/mavros/set_mode ↔ 모드 변경 요청
3. PX4 파라미터 세팅
먼저, 드론을 이륙시키기 위해서는 미리 설정되어 있는 PX4의 안전로직들을 통과해야 한다. 이러한 로직들로는
1. GCS가 연결되어 있는지 (PX4는 Qgroundcontrol을 기본 GCS로 사용)
2. GPS가 연결되어 있는지
3. Radio controller (조종기, transmitter)가 연결되어 있는지
등등이 있는데, gazebo시뮬레이션을 GCS연결 없이 수행하기 위해서는 1번의 GCS failsafe를 해지해야 합니다. 이를 위해서 다음의 명령어로 설정할 수 있습니다
param set NAV_DLL_ACT 0
이제 여기까지 설정하면 offboard 모드로 드론을 이륙할 준비가 된 것입니다. 아래의 간단한 코드로 드론을 자동이륙할 수 있습니다.
4. Offboard 제어 노드 예제 (Python, offboard.py)
코드 흐름 요약
- 20 Hz setpoint → PX4가 “활성 외부 컨트롤러”로 인식
- Arm 요청 → 프로펠러 스핀업
- 모드 전환 → Offboard 진입
- 호버 유지 → setpoint = (0,0,3 m) 스트림 지속
import rclpy
from rclpy.node import Node
from mavros_msgs.srv import CommandBool, SetMode
from geometry_msgs.msg import PoseStamped
class OffboardTakeoffNode(Node):
def __init__(self):
super().__init__('offboard_takeoff')
# Publishers
self.pose_pub = self.create_publisher(PoseStamped, '/mavros/setpoint_position/local', 10)
# Service clients
self.arming_client = self.create_client(CommandBool, '/mavros/cmd/arming')
self.mode_client = self.create_client(SetMode, '/mavros/set_mode')
# Setpoint 메시지 생성
self.target_pose = PoseStamped()
self.target_pose.pose.position.x = 0.0
self.target_pose.pose.position.y = 0.0
self.target_pose.pose.position.z = 3.0 # 이륙 고도 3m
# 주기적으로 퍼블리시 시작
self.timer = self.create_timer(0.05, self.timer_callback) # 20Hz
# flag
self.setpoint_sent = 0
self.armed = False
self.offboard_mode_set = False
def timer_callback(self):
self.target_pose.header.stamp = self.get_clock().now().to_msg()
self.pose_pub.publish(self.target_pose)
if self.setpoint_sent < 40: # 약 2초 동안 Setpoint 보내기
self.setpoint_sent += 1
return
if not self.armed:
self.arm_drone()
elif not self.offboard_mode_set:
self.set_offboard_mode()
def arm_drone(self):
if self.arming_client.service_is_ready():
req = CommandBool.Request()
req.value = True
future = self.arming_client.call_async(req)
self.armed = True
self.get_logger().info("Arming 요청 보냈습니다!")
def set_offboard_mode(self):
if self.mode_client.service_is_ready():
req = SetMode.Request()
req.custom_mode = 'OFFBOARD'
future = self.mode_client.call_async(req)
self.offboard_mode_set = True
self.get_logger().info("Offboard 모드 전환 요청 보냈습니다!")
def main(args=None):
rclpy.init(args=args)
node = OffboardTakeoffNode()
rclpy.spin(node)
rclpy.shutdown()
if __name__ == '__main__':
main()
5. 실행 절차 요약
1. PX4 SITL 실행 (Gazebo + x500 모델 불러오기)
make px4_sitl gz_x500
2. MAVROS 실행 (PX4/ROS2 간의 통신, MAVLink <-> ROS2 토픽 변환)
ros2 launch mavros px4.launch fcu_url:=udp://:14540@127.0.0.1:14580
3. Offboard 노드 실행 (Arm -> Offboard mode 변경 -> Setpoint 로직 실행)
4번의 python script를 offboard.py로 저장했다고 하면, script 디렉토리에서 아래 명령 실행
python3 offboard.py
그러면 다음그림과 같이 3초 뒤 드론이 3m 상공에서 호버링하고 있는 드론을 확인할 수 있습니다
다음 글에서는 offboard.py 스크립트를 패키지화 하여 드론 제어 코드의 뼈대를 세웁니다. 어디서든 ros2 launch 한 줄로 드론을 띄워 보며, 본격 MPPI 제어기 개발 여정을 시작해 보겠습니다.
'Robotics > Control Theory' 카테고리의 다른 글
ROS2 × PX4로 시작하는 자율비행 드론 제어 (5) MPPI Controller 란? (2) | 2025.05.07 |
---|---|
ROS2 × PX4로 시작하는 자율비행 드론 제어 (4) ROS2 패키지 생성 (2) | 2025.05.05 |
ROS2 × PX4로 시작하는 자율비행 드론 제어 (2) PX4 + Ignition Gazebo + MAVROS2 연동 전체 형태 구성 (0) | 2025.05.02 |
ROS2 × PX4로 시작하는 자율비행 드론 제어 (1) 프로젝트 소개와 환경 세팅 (Ubuntu 24.04 + ROS2 Jazzy) (1) | 2025.05.01 |
ACADO Toolkit 이란? 2. Code Generation 폴더 변경 방법 (0) | 2022.03.04 |
댓글