[PX4 ROS 2 Programming] 4편: Offboard 제어 (드론 위치 및 궤적 제어)
안녕하세요! 자율 비행 로봇을 연구하고 개발하시는 대학생 및 연구원 여러분, 다시 뵙게 되어 반갑습니다.
지난 3편에서는 ROS 2와 PX4 간에 데이터를 주고받는 기초적인 Listener(구독자)와 Advertiser(발행자) 노드를 작성해 보며 통신망을 테스트했습니다. 시스템의 맥박이 뛰는 것을 확인하셨다면, 이제 본격적으로 드론의 뇌를 장악하여 우리가 원하는 대로 움직이게 만들 차례입니다.
이번 4편에서는 드론 프로그래밍의 핵심이자 꽃이라고 할 수 있는 외부 제어(Offboard Control) 모드를 활용하여, 드론에 시동을 걸고(Arming) 특정 좌표(고도 5m)로 이륙시켜 호버링하게 만드는 전체 과정을 구현해 보겠습니다.
1. Offboard 제어란 무엇인가요?
일반적으로 드론은 조종기의 스틱을 움직여 제어합니다. 하지만 자율 비행을 위해서는 컴퓨터(Companion Computer)가 조종기를 대신하여 비행 제어기(PX4)에 목표 위치, 속도, 또는 추력 명령을 내려야 합니다. 이처럼 **외부의 컴퓨터나 ROS 2 노드가 직접 비행 명령을 내리는 비행 모드를 ‘Offboard(오프보드) 모드’**라고 부릅니다.
🚨 Offboard 모드 진입의 핵심: “2Hz 심장박동(Heartbeat)”
실제 드론 비행에서 Offboard 제어는 매우 위험할 수 있습니다. 만약 코드가 멈춰서 드론이 제어 명령을 받지 못하게 되면 자칫 큰 사고로 이어질 수 있기 때문입니다.
따라서 PX4 시스템은 매우 엄격한 안전 조건(Failsafe)을 요구합니다. PX4가 Offboard 모드로 전환하고 시동을 허락하기 위해서는, 사전에 최소 2Hz(초당 2번) 이상의 주기로 OffboardControlMode 메시지와 TrajectorySetpoint 메시지가 지속적으로 전달되어야 합니다. 만약 비행 중 이 메시지의 수신 주기가 2Hz 밑으로 떨어지면, PX4는 즉시 Offboard 모드를 해제하고 안전 모드(예: 제자리 호버링 또는 착륙)로 강제 전환합니다.

2. Offboard 제어 노드 작성하기
이제 드론을 고도 5m로 이륙시키고, 기체 방향(Yaw)을 180도 회전시키는 C++ ROS 2 노드를 작성해 보겠습니다. 앞서 설명한 “심장박동” 조건을 만족하기 위해 우리는 100ms(10Hz) 주기의 타이머를 사용하여 메인 루프를 구성할 것입니다.
전체 코드는 크게 세 부분의 메시지 발행으로 나뉩니다.
- OffboardControlMode: 위치 제어, 속도 제어 등 어떤 방식의 제어를 할 것인지 PX4에 알려줍니다.
- TrajectorySetpoint: 목표 좌표(X, Y, Z)와 기수 방향(Yaw)을 지시합니다.
- VehicleCommand: Offboard 모드로의 변경과 시동(Arm) 명령을 내립니다.
다음은 이를 모두 포함한 예제 코드(offboard_control.cpp)입니다. 코드를 천천히 읽어보세요.
#include <rclcpp/rclcpp.hpp>
#include <px4_msgs/msg/offboard_control_mode.hpp>
#include <px4_msgs/msg/trajectory_setpoint.hpp>
#include <px4_msgs/msg/vehicle_command.hpp>
using namespace std::chrono_literals;
class OffboardControl : public rclcpp::Node
{
public:
OffboardControl() : Node("offboard_control")
{
// 퍼블리셔 생성
offboard_control_mode_publisher_ = this->create_publisher<px4_msgs::msg::OffboardControlMode>("/fmu/in/offboard_control_mode", 10);
trajectory_setpoint_publisher_ = this->create_publisher<px4_msgs::msg::TrajectorySetpoint>("/fmu/in/trajectory_setpoint", 10);
vehicle_command_publisher_ = this->create_publisher<px4_msgs::msg::VehicleCommand>("/fmu/in/vehicle_command", 10);
// 100ms(10Hz) 주기 타이머 콜백 설정
auto timer_callback = [this]() -> void {
// 처음 10번의 주기(1초) 동안은 Setpoint만 발행하여 PX4를 준비시킵니다.
if (offboard_setpoint_counter_ == 10) {
// 10번의 Setpoint가 전달된 후, 모드를 Offboard로 변경하고 시동을 겁니다.
this->publish_vehicle_command(px4_msgs::msg::VehicleCommand::VEHICLE_CMD_DO_SET_MODE, 1, 6);
this->arm();
}
// 매 주기마다 제어 모드와 목표 궤적을 발행 (2Hz 이상 유지 필수)
publish_offboard_control_mode();
publish_trajectory_setpoint();
if (offboard_setpoint_counter_ < 11) {
offboard_setpoint_counter_++;
}
};
timer_ = this->create_wall_timer(100ms, timer_callback);
}
void arm()
{
publish_vehicle_command(px4_msgs::msg::VehicleCommand::VEHICLE_CMD_COMPONENT_ARM_DISARM, 1.0, 0.0);
RCLCPP_INFO(this->get_logger(), "Arm command send");
}
private:
rclcpp::TimerBase::SharedPtr timer_;
rclcpp::Publisher<px4_msgs::msg::OffboardControlMode>::SharedPtr offboard_control_mode_publisher_;
rclcpp::Publisher<px4_msgs::msg::TrajectorySetpoint>::SharedPtr trajectory_setpoint_publisher_;
rclcpp::Publisher<px4_msgs::msg::VehicleCommand>::SharedPtr vehicle_command_publisher_;
uint64_t offboard_setpoint_counter_ = 0;
// 제어 모드 설정 (위치 제어 활성화)
void publish_offboard_control_mode()
{
px4_msgs::msg::OffboardControlMode msg{};
msg.position = true; // 위치 제어 활성화
msg.velocity = false;
msg.acceleration = false;
msg.attitude = false;
msg.body_rate = false;
msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
offboard_control_mode_publisher_->publish(msg);
}
// 목표 좌표(고도 5m, Yaw 180도) 지시
void publish_trajectory_setpoint()
{
px4_msgs::msg::TrajectorySetpoint msg{};
// 중요: PX4는 NED(북-동-하) 좌표계를 사용하므로, Z축 -5.0이 상공 5m를 의미합니다!
msg.position = {0.0, 0.0, -5.0};
msg.yaw = -3.14; // [-PI:PI] 범위 (약 -180도)
msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
trajectory_setpoint_publisher_->publish(msg);
}
// 비행 제어기로 MAVLink 명령어 송신
void publish_vehicle_command(uint16_t command, float param1, float param2)
{
px4_msgs::msg::VehicleCommand msg{};
msg.param1 = param1;
msg.param2 = param2;
msg.command = command;
msg.target_system = 1;
msg.target_component = 1;
msg.source_system = 1;
msg.source_component = 1;
msg.from_external = true;
msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
vehicle_command_publisher_->publish(msg);
}
};
int main(int argc, char *argv[])
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<OffboardControl>());
rclcpp::shutdown();
return 0;
}
3. 코드 핵심 파헤치기
코드가 다소 길어 보이지만, 알고 보면 각 기능 단위로 명확히 나뉘어 있습니다. 연구원분들이 꼭 짚고 넘어가야 할 핵심 개념을 설명해 드리겠습니다.
1) timer_callback 내의 초기 1초(10주기) 대기 로직
앞서 설명했듯, PX4는 OffboardControlMode를 수신하기 전까지는 절대 Offboard 모드로 전환해주지 않습니다. 따라서 루프가 실행되면 처음 10번의 주기(100ms * 10 = 1초) 동안은 단순히 제어 모드와 목표 좌표만 PX4로 계속 쏴줍니다. PX4가 내부적으로 *”아, 외부에서 안정적으로 명령이 들어오고 있구나!”*라고 인지하게 한 뒤, 10번째 주기에 도달했을 때 비로소 **모드 변경(VEHICLE_CMD_DO_SET_MODE)**과 시동(arm()) 명령을 내리는 것입니다.
2) publish_offboard_control_mode()
우리는 특정 좌표로 날아가는 제어를 할 것이므로 msg.position = true로 설정하고, 나머지 속도나 가속도 제어 등은 모두 false로 꺼둡니다. 이 메시지는 PX4에게 제어의 ‘방식(Type)’을 알려주는 역할을 합니다.
3) publish_trajectory_setpoint()와 좌표계 주의사항
연구자분들이 시뮬레이션을 돌려보고 가장 당황하는 부분입니다. msg.position = {0.0, 0.0, -5.0}으로 Z값을 음수로 설정했습니다. 왜 5m 위로 올라가는데 -5.0을 넣을까요? 2편에서 다루었던 **좌표계(Frames)**를 떠올려보세요! ROS 2는 기본적으로 위쪽이 양수인 ENU(동-북-상)를 쓰지만, PX4의 메시지는 명시적인 예외가 없다면 NED(북-동-하) 좌표계를 기본으로 채택합니다. Z축의 양(+)의 방향이 ‘아래쪽(Down)’이므로, 하늘로 5m 올라가려면 반드시 -5.0을 입력해야 합니다. ROS 2의 ENU 좌표계를 그대로 받아오신다면, frame_transforms 라이브러리를 사용해 Z축을 뒤집고 회전시켜 주는 과정을 반드시 거치셔야 합니다.
4) publish_vehicle_command()
VehicleCommand 메시지는 PX4 시스템에 가장 강력하고 직관적으로 명령(Takeoff, Land, Arm, Mode Change 등)을 내릴 수 있는 수단입니다. 내부적으로 MAVLink의 MAV_CMD 규칙과 정확히 매핑됩니다.
4. 시뮬레이션에서 노드 실행 및 확인
코드를 성공적으로 작성하셨다면, 작업 공간(Workspace)을 빌드하고 실행해 봅니다.
터미널을 열고 코드를 빌드합니다.
cd ~/ws_offboard_control/
source /opt/ros/humble/setup.bash
colcon build
- Micro XRCE-DDS Agent와 PX4 Gazebo 시뮬레이터가 다른 터미널에서 실행 중인지 확인하세요. (참고: 기본 설정상 QGroundControl(QGC) 등 지상 통제국 프로그램이 연결되어 있어야 시동이 걸립니다. 비상시 수동 제어로 권한을 넘길 수 있도록 보장하기 위함입니다).
- 빌드한 워크스페이스를 소스하고 노드를 실행합니다.
source install/local_setup.bash
ros2 run px4_ros_com offboard_control

노드가 실행되면 시뮬레이터 안의 드론이 힘차게 프로펠러를 돌리며(Arming) 하늘로 솟아올라, 정확히 고도 5m 지점에 멈춰서 호버링(Hovering) 하는 짜릿한 모습을 목격하실 수 있을 것입니다! 그리고 코드가 실행되는 동안 기수(Yaw)는 180도로 회전한 상태를 유지합니다.
마치며
축하합니다! 이번 4편을 통해 여러분은 드론 자율 비행의 심장부인 Offboard 제어의 원리를 파악하고, C++ 노드로 기체의 위치를 성공적으로 지배하게 되었습니다. 100ms 타이머로 안전망을 구성하는 로직과 좌표계의 함정만 유의하신다면, 앞으로 여러분의 아이디어를 담은 어떠한 복잡한 궤적 생성 알고리즘도 이 틀 안에 쉽게 녹여내실 수 있습니다.
다음 **5편: 심화 기법 (서비스 서버 및 다중 기체 시뮬레이션)**에서는 단순히 메시지를 쏘는 것을 넘어서, “시동이 잘 걸렸는지” 응답을 확실히 받아내는 VehicleCommand 서비스(Service) 통신 기법과 단일 컴퓨터로 여러 대의 군집 드론을 제어하는 다중 기체(Multi-Vehicle) 시뮬레이션 방법에 대해 다뤄보겠습니다.
질문이 있으시다면 언제든 댓글로 남겨주시고, 연구와 과제 모두 좋은 결과 있으시길 응원합니다. 다음 편에서 뵙겠습니다!
YouTube 강좌

Author: maponarooo, CEO of QUAD Drone Lab
Date: February 28, 2026
