작성한 offboard_node.py
를
ROS 2 Humble + PX4 SITL + Gazebo Classic 환경에서 실행하는 과정이다.
Ubuntu 22.04 에서 진행하였다.
PX4 SITL: 드론 비행 컨트롤러를 소프트웨어로 시뮬레이션
Gazebo Classic: 실제 물리환경/드론 모델을 시뮬레이션
MAVROS2 (mavros_node): PX4와 ROS 2 노드를 연결해주는 브릿지
Node = ROS 그래프 안에서 실행되는 프로세스/객체
offboard_node.py
구조from rclpy.node import Node
class OffboardTakeoffNode(Node): # 노드 정의
def __init__(self):
super().__init__('offboard_takeoff') # 노드 이름 : "offboard_takeoff"
def main(args=None): # 노드 실행 함수
rclpy.init(args=args)
node = OffboardTakeoffNode() # 노드 객체 생성
rclpy.spin(node) # 노드를 ROS2 이벤트 루프에 등록
rclpy.shutdown()
설치 & 준비
# ROS 2 Humble 설치 후 기본 빌드 도구
sudo apt update
sudo apt install -y python3-colcon-common-extensions python3-rosdep \
python3-colcon-mixin python3-vcstool build-essential
# ROS 2 workspace 준비
mkdir -p ~/colcon_ws/src
cd ~/colcon_ws
sudo apt install -y ros-humble-mavros ros-humble-mavros-msgs
# GeographicLib 데이터셋 설치 (MAVROS 필수)
sudo /opt/ros/humble/lib/mavros/install_geographiclib_datasets.sh
cd ~
git clone https://github.com/PX4/PX4-Autopilot.git --recursive
cd PX4-Autopilot
# PX4 SITL + Gazebo Classic 빌드 및 실행
make px4_sitl gazebo-classic
→ 이 터미널은 PX4 SITL 프로세스를 유지해야 한다.
offboard_control 패키지 준비
~/colcon_ws/src/offboard_control/
├── package.xml
├── setup.py
├── setup.cfg
├── resource/offboard_control
└── offboard_control
├── __init__.py
└── offboard_node.py # 실행하고자 하는 코드
code 명령어가 설치되어 있지 않다면 먼저 설치한다.
sudo snap install --classic code
colcon 워크스페이스를 VSCode로 연다.
code ~/colcon_ws
→ colcon_ws 디렉토리가 VSCode에서 열리게 되며,
그 안의 offboard_control 패키지에서 코드 작성이 가능하다.
빌드 과정
cd ~/colcon_ws
rm -rf build/ install/ log/
colcon build --merge-install # 패키지 빌드
source /opt/ros/humble/setup.bash # ROS 2 환경
source install/setup.bash # 워크스페이스 반영
ros2 pkg executables offboard_control
# → offboard_control offboard_node
실행 과정
cd ~/PX4-Autopilot
make px4_sitl gazebo-classic
# 예시 (14540 리슨, 14557 송신 패턴)
ros2 run mavros mavros_node --ros-args \
-p fcu_url:=udp://:14540@127.0.0.1:14557 \
-p gcs_url:=udp://@127.0.0.1:14550
source /opt/ros/humble/setup.bash
source ~/colcon_ws/install/setup.bash
ros2 run offboard_control offboard_node
실행 결과 확인
ros2 topic hz /mavros/setpoint_position/local
________________________________________________
# 출력 (예시)
average rate: 20.001
min: 0.049s max: 0.051s std dev: 0.00033s window: 22
average rate: 20.003
min: 0.049s max: 0.051s std dev: 0.00032s window: 43
average rate: 20.001
min: 0.049s max: 0.051s std dev: 0.00035s window: 63
average rate: 20.001
min: 0.049s max: 0.051s std dev: 0.00033s window: 84
average rate: 20.001
min: 0.049s max: 0.051s std dev: 0.00032s window: 104
average rate: 20.002
min: 0.049s max: 0.051s std dev: 0.00033s window: 125
ros2 topic echo /mavros/state --once
________________________________________________
# 출력 (예시)
header:
stamp:
sec: 1756090198
nanosec: 986522381
frame_id: ''
connected: true
armed: true
guided: false
manual_input: false
mode: OFFBOARD
system_status: 4
ros2 topic echo /mavros/local_position/pose --once
# z ≈ 3.0 m
________________________________________________
# 출력 (예시)
header:
stamp:
sec: 1756090242
nanosec: 425380024
frame_id: map
pose:
position:
x: 0.06275475025177002
y: -0.06464655697345734
z: 2.9876708984375
orientation:
x: 0.0025375570402642223
y: 0.006539057863229459
z: 0.0002385090157231988
w: -0.999975411273047
착륙하기
# 자동 착륙 모드
ros2 service call /mavros/set_mode mavros_msgs/srv/SetMode "{custom_mode: 'AUTO.LAND'}"
# 땅에 닿으면 시동 해제
ros2 service call /mavros/cmd/arming mavros_msgs/srv/CommandBool "{value: false}"
PX4에 'AUTO.LAND'
모드 전환 요청 → 비행 컨트롤러(PX4) 가 자체 알고리즘으로 착륙 절차 수행.