이 블로그 시리즈에서는 Gazebo + ROS 2 + PX4(MAVROS)를 활용해 드론을 제어하고, 최적 제어 알고리즘 Model Predictive Path Integral (MPPI) 를 직접 구현하는 과정을 기록합니다. 이후에는 더 진화된 강화학습(RL) 기반 제어로까지 확장하며, 최신 오픈소스 생태계가 실제 연구·개발 파이프라인에서 어떻게 유기적으로 엮이는지 보여드릴 예정입니다.

이번 글에서는 지난 글까지 이론으로 다졌던 드론의 ‘운동 모델’을 단계별로 설명하면서 실제 코드로 옮겨보겠습니다. 이전 글에서 설명드린것 처럼 MPPI 컨트롤러는 "지금 입력을 주면 0.5초 뒤엔 어디 있을까?"를 수백 번 계산해 가장 좋은 입력을 고르는 방법입니다. 이러한 예측을 해주는 블랙박스가 바로 오늘 만들어 볼 운동모델입니다. 이를 통해 모터 PWM → 추력·토크 → 가속도·속도·위치가 전부 계산되고, MPPI·MPC 등 어떤 컨트롤러도 붙일 수 있습니다.
초보자 팁: 만약 드론이나 로보틱스에 처음이시라면, 운동 모델이란 드론의 움직임을 물리 법칙(뉴턴의 법칙 등)으로 예측하는 '수학적 시뮬레이터'예요. 마치 게임에서 캐릭터가 점프할 때 중력을 계산하는 거랑 비슷해요. 이 글에서 나오는 수식들은 단계별로 풀어 설명할 테니, 천천히 따라오세요. 배경 지식이 부족하다면 시리즈 첫 글부터 읽어보는 걸 추천합니다!
1. 파라미터 정리: 드론의 물리적 특성 한눈에 보기
드론의 운동 모델을 만들기 전에, 드론의 기본 '스펙'을 정리 하겠습니다. 이 값들은 실제 드론(여기선 X500 모델)을 기반으로 하였습니다. 이 테이블을 보면서 "드론이 왜 이런 값이 필요한가?"를 생각해보세요. 예를 들어, 질량(mass)은 드론이 얼마나 무거운지, 그래서 추력이 얼마나 세야 떠오를 수 있는지를 결정합니다.
| 변수 | 값 (예시) | 의미 |
| 기체 관련 | ||
| mass | 2.0 kg | 추력 → 가속도 $a=F/m$ 변환 |
| Ixx, Iyy, Izz | 0.022 · 0.022 · 0.040 kg·m² | 롤·피치·요 축 관성 |
| arm_length | 0.24 m | 모터축 ↔ 기체 중심 거리 |
| 모터 관련 | ||
| motor_constant (k_f) | 8.55×10−68.55×10^{-6} N/(rad/s)² | RPM² → 추력 |
| moment_constant (k_m) | 0.016 N·m/(rad/s)² | RPM² → 반작용 요 토크 |
| max_rot_velocity |
1000 rad/s | 실제 모터의 회전 속도 한계 반영 |
질량과 관성
- $mass$: 우리가 시뮬레이션에서 사용하는 드론은 2 kg짜리 X500 모델 입니다. 예: 2kg 드론에 20N 추력을 주면 가속도는 10m/s² (위로 솟아오름) (F=ma --> a=F/m).
- 관성 는 드론의 프레임이 좌우 대칭이어서, 롤(좌우 기울기) · 피치(앞뒤 기울기) 움직임이 비슷하다는 뜻입니다.
- $I_{zz}$ 가 더 큰 이유는 모터와 프로펠러가 수평으로 퍼져 있어서 회전 중심으로부터의 거리가 더 멀기 때문입니다. (마치 피겨 스케이터가 팔을 벌리면 회전이 느려지는 원리)
팔 길이 (arm_length = 0.24 )
- “모터축에서 기체 중심” 거리 입니다. 이 길이는 롤과 피치 토크를 힘으로 바꿀 때 지렛대 역할을 합니다. 예: 문을 밀 때 손잡이 끝에서 밀면 쉽게 열리듯, 팔이 길면 적은 힘으로 큰 회전 가능.
- 24 cm 라면 500 급 프레임에 딱 맞는 크기 입니다. 보통 팔 길이 *2 해서 기체의 크기를 따집니다. (이경우에는 240*2: 480 -> 500 급)
중력 벡터 g
- 지구의 중력 가속도(-9.81 m/s²)를 z축에 적용합니다. ENU 좌표계(동쪽-북쪽-위)를 따라 z축의 위쪽이 (+)이고 아래쪽이 (-)로 설정됩니다. 이 값은 시뮬레이션마다 항상 더해져 추력이 없을 경우 드론이 땅으로 끌려 내려가게 만듭니다. 예: 드론이 떠 있으려면 추력이 중력만큼 세야 하죠 (호버링 상태).
모터·프로펠러 상수
- motor_constant ($k_f$)는 모터 RPM²을 추력 N(뉴턴)으로 바꾸는 비율 입니다
- moment_constant ($k_m$) 은 RPM²을 토크 N·m로 바꾸는 비율 입니다. 이 값들은 실제 프로펠러 테스트나 System ID 로 실측·식별해야 합니다.
- time_constant_up(0.0125초), time_constant_down(0.025초): 모터가 속도를 올릴 때(가속)와 내릴 때(감속)의 반응 속도 입니다. 가속 (전류를 공급받아 모터를 가속)이 감속 (프로펠러의 관성과 공기저항) 보다 빠른 게 일반적이죠. 이 값 덕에 모터가 현실처럼 부드럽게 반응합니다.
- max_rot_velocity (1000 rad/s ≈ 9500 RPM): 모터가 터무니 없이 빠르게 돌지 않도록 제한하는 안전장치 입니다.
- motor_directions [+1, +1, −1, −1]: 앞오른쪽과 뒤왼쪽 모터는 반시계 (CCW), 나머지는 시계 (CW) 방향으로 회전합니다. 요 토크를 계산할 때 각 모터의 회전 부호가 필요합니다.
실제 드론을 이용한 실험에서는 $k_f, k_m, I_{xx}...$ 등의 값은 모두 실측된 값으로 넣어주어야 합니다. 우리는 gazebo simulation에서 x500기체를 활용해 먼저 실험할 것이므로 시뮬레이션 상에 구현된 값을 넣어주겠습니다.
1. x500 기체 모델: [기체 무게, $I_{xx}, I_{yy}, I_{zz}$, arm 길이] 등이 정의 되어 있음
2. x500 모터 모델: [$k_f, k_m$, 모터 최대 회전속도] 등이 정의 되어 있음
그리고 이를 코드로 구현하면 다음과 같습니다.
import numpy as np
class QuadcopterDynamics:
"""쿼드로터 운동 모델"""
def __init__(self):
# Physical parameters
self.mass = 2.0 # kg
self.Ixx = 0.0216667 # kg⋅m²
self.Iyy = 0.0216667 # kg⋅m²
self.Izz = 0.04 # kg⋅m²
self.arm_length = 0.24 # m
self.max_thrust = 20.0 # N
self.min_thrust = 0.0 # N
self.g = np.array([0, 0, -9.81]) # m/s²
# Motor parameters
self.motor_constant = 8.54858e-06
self.moment_constant = 0.016
self.time_constant_up = 0.0125
self.time_constant_down = 0.025
self.max_rot_velocity = 1000.0
self.motor_directions = np.array([1, 1, -1, -1]) # CCW/CW
self.motor_speeds = np.zeros(4)
테스트
# 드론 초기화
drone = QuadcopterDynamics()
# 파라미터 확인
print(f"질량: {drone.mass} kg")
print(f"롤 관성: {drone.Ixx} kg·m²")
print(f"팔 길이: {drone.arm_length} m")
2. 모터모델: 제어 입력을 모터 속도로 바꾸기 - 뇌의 명령을 근육으로!
드론은 4개의 모터로 움직입니다. 그런데 MPPI로부터 나오는 제어 입력은 다음과 같습니다. $u$: 총 추력 T, 롤 Mφ, 피치 Mθ, 요 Mψ. 결국 제어기는 드론에게 이렇게 말하는 것과도 같습니다.
"너가 앞으로 떠오르려면 총 몇 N의 힘이 필요하고, 몸을 얼마나 기울이고, 또 얼마나 회전해야 해"
> "총 추력 15N, 롤 5° 기울어, 피치 2° 숙여, 요 10° 회전해"
하지만 드론은 이 말을 못 알아듣습니다. 드론이 할 수 있는 건 각 모터를 얼마나 빨리 돌려라 뿐이죠. 결국, 각 모터의 회전속도(RPM)를 바꾸는 것입니다. 따라서 우리는 제어 입력을 4개 모터의 속도로 바꾸는 함수를 만들어야 합니다. 이 과정을 6단계로 나누어 설명드리겠습니다.
- 총 추력 클리핑: 비현실적인 입력은 잘라내기
먼저, 입력으로 받은 총 추력 $u[0]$값이 너무 작거나 (음수) 크면 (드론의 실제 최대추력 이상) 미리 걸러냅니다. 드론은 공기 속에서 작동하는 실제 물체이기 때문에 역추력(음수)은 물리적으로 불가능하고, 너무 큰 추력도 모터의 한계를 초과할 수 있기 때문입니다.- min_thrust = 0.0 → 역추력 방지
- max_thrust = 20.0 N → 모터한계 설정
thrust = np.clip(u[0], self.min_thrust, self.max_thrust)
- 토크를 힘으로 변환
입력으로 들어온 롤, 피치, 요의 회전 토크는 각 모터가 얼마만큼 더 돌거나 덜 돌아야 하는지로 바꿔야 합니다.- 롤/피치 모멘트는 드론 중심에서의 팔 길이를 기준으로 환산합니다. 팔이 길수록 적은 힘으로도 큰 회전이 생깁니다.
- 요 모멘트는 모터 4개가 각각 회전 방향이 반대여서, 네 개의 회전 방향을 균등하게 고려해야 합니다.
roll_effect = u[1] / (2 * self.arm_length)
pitch_effect = u[2] / (2 * self.arm_length)
yaw_effect = u[3] / (4 * self.moment_constant)
- 추력과 모멘트 조합
각 모터에 “총 추력의 ¼”에 모멘트 효과를 더하거나 빼서 힘을 분배해요.
self.motor_speeds[0] = thrust/4 + roll_effect + pitch_effect + yaw_effect
self.motor_speeds[1] = thrust/4 + roll_effect - pitch_effect + yaw_effect
self.motor_speeds[2] = thrust/4 - roll_effect + pitch_effect - yaw_effect
self.motor_speeds[3] = thrust/4 - roll_effect - pitch_effect - yaw_effect
- 회전 방향 적용
CCW 모터는 +1, CW 모터는 -1로 부호를 곱해요. 이렇게 해야 나중에 RPM²로 계산할 때 요 토크가 제대로 상쇄됩니다. - RPM 상한 클리핑
모터가 물리적으로 불가능한 속도로 돌지 않도록 최대 회전 속도(1000 rad/s)로 제한해요. 이걸 안 하면 시뮬레이터가 터무니없는 명령을 시도할 수 있어요.
# 회전 방향 (CCW/CW) 적용
self.motor_speeds *= self.motor_directions
# 최대 속도 제한 (음수는 0으로 클리핑)
self.motor_speeds = np.clip(self.motor_speeds, 0, self.max_rot_velocity)
- 결과 반환
네 모터의 RPM을 배열로 반환해요. 이 값은 다음 0.05초 동안 “이 속도로 돌았다”고 가정합니다.
전체코드는 다음과 같습니다.
def motor_model(self, u):
"""Convert control inputs to motor speeds."""
# u[0] is thrust, u[1:4] are roll, pitch, yaw moments
thrust = np.clip(u[0], self.min_thrust, self.max_thrust)
# Convert moments to motor speeds
roll_effect = u[1] / (2 * self.arm_length)
pitch_effect = u[2] / (2 * self.arm_length)
yaw_effect = u[3] / (4 * self.moment_constant)
# Calculate individual motor speeds
self.motor_speeds[0] = thrust/4 + roll_effect + pitch_effect + yaw_effect
self.motor_speeds[1] = thrust/4 + roll_effect - pitch_effect + yaw_effect
self.motor_speeds[2] = thrust/4 - roll_effect + pitch_effect - yaw_effect
self.motor_speeds[3] = thrust/4 - roll_effect - pitch_effect - yaw_effect
# Apply motor direction and limits
self.motor_speeds *= self.motor_directions
self.motor_speeds = np.clip(self.motor_speeds, 0, self.max_rot_velocity)
return self.motor_speeds
테스트
# 드론 초기화
drone = QuadcopterDynamics()
# 테스트 1: 호버링 (추력만, 토크 없음)
hover_thrust = drone.mass * 9.81 # 19.62N
u_hover = np.array([hover_thrust, 0, 0, 0])
motor_speeds = drone.motor_model(u_hover)
print("호버링:")
print(f"모터 속도: {motor_speeds} rad/s")
print(f"모든 모터가 같은 속도로 회전해야 함: {np.allclose(motor_speeds, motor_speeds[0])}")
# 테스트 2: 롤 제어 (왼쪽 기울이기)
u_roll = np.array([hover_thrust, 2.0, 0, 0]) # +2N·m 롤토크
motor_speeds_roll = drone.motor_model(u_roll)
print("\n롤 제어 (왼쪽):")
print(f"왼쪽 모터(3,4)가 더 빨라야 함")
print(f"모터1: {motor_speeds_roll[0]:.1f} rad/s")
print(f"모터2: {motor_speeds_roll[1]:.1f} rad/s")
print(f"모터3: {motor_speeds_roll[2]:.1f} rad/s (더 빠름)")
print(f"모터4: {motor_speeds_roll[3]:.1f} rad/s (더 빠름)")
결과
호버링:
모터 속도: [476. 476. 476. 476.] rad/s
모든 모터가 같은 속도로 회전해야 함: True
롤 제어 (왼쪽):
왼쪽 모터(3,4)가 더 빨라야 함
모터1: 416.7 rad/s
모터2: 416.7 rad/s
모터3: 535.2 rad/s (더 빠름)
모터4: 535.2 rad/s (더 빠름)'Robotics > Control Theory' 카테고리의 다른 글
| ROS2 × PX4로 시작하는 자율비행 드론 제어 (7-2) 쿼드로터 운동 모델 - 다이내믹스와 회전행렬 (0) | 2026.01.12 |
|---|---|
| ROS2 × PX4로 시작하는 자율비행 드론 제어 (6) 쿼드로터 운동 모델 (2) | 2025.05.19 |
| ROS2 × PX4로 시작하는 자율비행 드론 제어 (5) MPPI Controller 란? (2) | 2025.05.07 |
| ROS2 × PX4로 시작하는 자율비행 드론 제어 (4) ROS2 패키지 생성 (2) | 2025.05.05 |
| ROS2 × PX4로 시작하는 자율비행 드론 제어 (3) Offboard Mode 기초 (2) | 2025.05.04 |