JSBSimでシミュレーションを実行すると、「0.1秒でNaN発散」「トリム計算が収束しない」といった問題に直面することがあります。これらの多くは空力微係数の欠落や符号ミスが原因です。

本記事では、JSBSim機体XMLで使用する空力微係数の基礎を解説します。

この記事で学べること#

  • 空力微係数(Aerodynamic Derivatives)とは何か
  • 静安定微係数と動安定微係数の違い
  • 各係数の役割と符号規則
  • 推奨値の範囲(200g級小型固定翼機)
  • よくあるトラブルとの関連

対象読者#

  • JSBSim機体XMLを作成する方
  • シミュレーション発散やトリム失敗に悩んでいる方
  • 空力微係数の役割を理解したい方

空力微係数とは#

空力微係数(Aerodynamic Derivatives)は、機体の姿勢や速度の変化に対する空力の応答を表す係数です。

定義:

係数 = ∂(力またはモーメント) / ∂(状態変数)

例:

  • CLalpha: 迎角(α)の変化に対する揚力係数(CL)の変化率
  • Cmalpha: 迎角(α)の変化に対するピッチングモーメント係数(Cm)の変化率
  • Cmq: ピッチレート(q)の変化に対するピッチングモーメント係数(Cm)の変化率

これらの係数により、機体の安定性が決まります。


空力微係数の分類#

空力微係数は大きく2つに分類されます。

1. 静安定微係数(Static Stability Derivatives)#

定義: 機体の姿勢(迎角・横滑り角)に対する力・モーメントの変化率

主な係数:

  • Cmalpha: 迎角に対するピッチングモーメント(縦安定性)
  • CLalpha: 迎角に対する揚力(揚力傾斜)
  • Cnbeta: 横滑り角に対するヨーイングモーメント(方向安定性)

2. 動安定微係数(Dynamic Stability Derivatives)#

定義: 機体の角速度(ピッチレート・ロールレート・ヨーレート)に対するモーメントの変化率

主な係数:

  • Cmq: ピッチレートに対するピッチングモーメント(ピッチ減衰)
  • Clp: ロールレートに対するローリングモーメント(ロール減衰)
  • Cnr: ヨーレートに対するヨーイングモーメント(ヨー減衰)

主要な空力微係数の詳細#

静安定微係数#

Cmalpha(縦安定性)⭐⭐⭐⭐⭐#

定義: 迎角の変化に対するピッチングモーメントの変化率

Cmalpha = ∂Cm/∂α

役割: 縦安定性(Longitudinal Stability)を決定

符号規則: 必ず負の値

  • 負の値: 迎角が増加すると機首下げモーメント発生(安定)
  • 正の値: 迎角が増加すると機首上げモーメント発生(不安定、ループ発散)

推奨値: -0.50 /rad(200g級小型固定翼機)

典型範囲: -1.5 ~ -0.1 /rad

重要性: ⭐⭐⭐⭐⭐(トリム計算収束に決定的)

JSBSim XML実装例:

<function name="aero/moment/Pitch_alpha">
  <description>Pitching moment due to alpha (Cmalpha: static stability)</description>
  <product>
    <property>aero/qbar-psf</property>
    <property>metrics/Sw-sqft</property>
    <property>metrics/cbarw-ft</property>
    <value>-0.50</value>  <!-- Cmalpha値、必ず負 -->
    <property>aero/alpha-rad</property>
  </product>
</function>

関連トラブル:

  • Cmalphaが正の値 → トリム計算が収束しない(E-2記事参照)

CLalpha(揚力傾斜)⭐⭐⭐#

定義: 迎角の変化に対する揚力係数の変化率

CLalpha = ∂CL/∂α

役割: 迎角変化に対する揚力の応答

符号規則: 必ず正の値

  • 迎角が増加すると揚力が増加(通常の翼)

推奨値: 5.0 /rad(200g級小型固定翼機)

典型範囲: 3.0 ~ 7.0 /rad

理論値: 2π ≈ 6.28 /rad(薄翼理論)

重要性: ⭐⭐⭐


Cnbeta(方向安定性)⭐⭐⭐#

定義: 横滑り角(β)の変化に対するヨーイングモーメントの変化率

Cnbeta = ∂Cn/∂β

役割: 方向安定性(Directional Stability)を決定

符号規則: 必ず正の値

  • 正の値: 横滑り発生時に機首が風上に向く(安定)

典型範囲: 0.05 ~ 0.15 /rad

重要性: ⭐⭐⭐(垂直尾翼の効果)


動安定微係数#

Cmq(ピッチレート減衰)⭐⭐⭐⭐⭐ 必須#

定義: ピッチレート(q)の変化に対するピッチングモーメントの変化率

Cmq = ∂Cm/∂(qc/2V)

ここで:

  • q: ピッチレート (rad/s)
  • c: 平均翼弦 (m)
  • V: 対気速度 (m/s)

役割: ピッチング運動の減衰(ダンパー効果)

符号規則: 必ず負の値

  • 負の値: ピッチレートを抑制(減衰効果)

推奨値: -12.0 /rad(200g級小型固定翼機)

典型範囲: -30.0 ~ -10.0 /rad

必須性: 🔴 絶対必須

  • Cmqなし → シミュレーション発散(0.1秒でNaN)

JSBSim XML実装例:

<function name="aero/moment/Pitch_rate">
  <description>Pitching moment due to pitch rate (Cmq: pitch rate damping)</description>
  <product>
    <property>aero/qbar-psf</property>
    <property>metrics/Sw-sqft</property>
    <property>metrics/cbarw-ft</property>
    <value>-12.0</value>  <!-- Cmq値、必ず負 -->
    <property>aero/ci2vel</property>
    <property>velocities/q-rad_sec</property>
  </product>
</function>

重要性: ⭐⭐⭐⭐⭐(省略不可)

関連トラブル:

  • Cmqなし → NaN発散(E-1記事参照)

Clp(ロールレート減衰)⭐⭐⭐#

定義: ロールレート(p)の変化に対するローリングモーメントの変化率

Clp = ∂Cl/∂(pb/2V)

ここで:

  • p: ロールレート (rad/s)
  • b: 翼幅 (m)
  • V: 対気速度 (m/s)

役割: ロール運動の減衰

符号規則: 必ず負の値

  • 負の値: ロールレートを抑制(減衰効果)

典型範囲: -0.5 ~ -0.1 /rad

重要性: ⭐⭐⭐(ロール安定性に影響)


Cnr(ヨーレート減衰)⭐⭐⭐#

定義: ヨーレート(r)の変化に対するヨーイングモーメントの変化率

Cnr = ∂Cn/∂(rb/2V)

ここで:

  • r: ヨーレート (rad/s)
  • b: 翼幅 (m)
  • V: 対気速度 (m/s)

役割: ヨー運動の減衰

符号規則: 必ず負の値

  • 負の値: ヨーレートを抑制(減衰効果)
  • 正の値: ヨーレート発散(不安定)

典型範囲: -0.15 ~ -0.03 /rad

重要性: ⭐⭐⭐(Spiral Mode安定性に影響)

関連トラブル:

  • Cnrが正の値 → ヨーレート発散

符号規則のまとめ#

係数 符号規則 物理的意味
Cmalpha 必ず負 迎角増加→機首下げ(縦安定)
CLalpha 必ず正 迎角増加→揚力増加
Cnbeta 必ず正 横滑り発生→機首が風上(方向安定)
Cmq 必ず負 ピッチレート→減衰効果
Clp 必ず負 ロールレート→減衰効果
Cnr 必ず負 ヨーレート→減衰効果

重要: 符号を間違えると機体が不安定になり、シミュレーションが発散します。


推奨値の範囲(200g級小型固定翼機)#

係数 推奨範囲 推奨値 単位 重要度
CL0 0.10 ~ 0.30 0.25 - ⭐⭐
CLalpha 3.0 ~ 7.0 5.0 /rad ⭐⭐⭐
CD0 0.020 ~ 0.080 0.028 - ⭐⭐⭐⭐⭐
Cmalpha -1.5 ~ -0.1 -0.50 /rad ⭐⭐⭐⭐⭐
Cmq -30.0 ~ -10.0 -12.0 /rad ⭐⭐⭐⭐⭐
Clp -0.5 ~ -0.1 -0.4 /rad ⭐⭐⭐
Cnr -0.15 ~ -0.03 -0.055 /rad ⭐⭐⭐

: 推奨値はArduPilot Rascal実証値に基づきます。


実装の優先順位#

空力微係数を実装する際の優先順位:

1. 最優先(🔴 必須)#

  1. Cmq: ピッチレート減衰(省略不可、0.1秒でNaN発散)
  2. Cmalpha: 縦安定性(トリム計算収束に必須)
  3. CD0: 有害抗力(トリム計算収束に必須)

2. 高優先(⭐⭐⭐)#

  1. CLalpha: 揚力傾斜(飛行特性に影響)
  2. Clp: ロールレート減衰(ロール安定性)
  3. Cnr: ヨーレート減衰(Spiral Mode安定性)

3. 中優先(⭐⭐)#

  1. CL0: ゼロ揚力係数(飛行特性の微調整)
  2. Cnbeta: 方向安定性(垂直尾翼効果)

アドバイス: まず🔴必須の3つを実装してください。これらがないとシミュレーションが成立しません。


よくあるトラブルと空力微係数の関係#

トラブル1: シミュレーション開始0.1秒でNaN発散#

原因: Cmqが欠落している

解決方法: PITCH軸にPitch_rate functionを追加

詳細: E-1: NaN発散トラブル


トラブル2: トリム計算が収束しない#

原因1: Cmalphaが正の値(縦不安定)

解決方法: Cmalpha値を負に修正(推奨: -0.50)

詳細: E-2: トリム失敗トラブル

原因2: CD0が過大(推力不足)

解決方法: CD0値を減らす(推奨: 0.028)

詳細: E-6: CD0過大トラブル


トラブル3: ヨーレートが発散する#

原因: Cnrが正の値(ヨー不安定)

解決方法: Cnr値を負に修正(推奨: -0.055)


空力微係数の調べ方#

自分の機体の空力微係数を知りたい場合:

方法1: 実測値を使用(最も正確)#

  • 風洞試験データ
  • 飛行試験データ

方法2: 参考機体の値を使用(推奨)#

  • ArduPilot Rascal(200g級固定翼機)
  • 類似の機体モデル

方法3: 理論計算(概算)#

  • CLalpha ≈ 2π ≈ 6.28 /rad(薄翼理論)
  • Cmalpha ≈ -(CG位置 - 空力中心位置) / 翼弦長

推奨: まずは方法2(参考機体の値)から始め、必要に応じて実測値で調整してください。


まとめ#

本記事では、JSBSim空力微係数の基礎を解説しました。

重要ポイント:

  1. 空力微係数は機体の安定性を決定する重要パラメータ
  2. 静安定微係数(Cmalpha, CLalpha, Cnbeta)と動安定微係数(Cmq, Clp, Cnr)の2種類
  3. 符号規則を守ることが重要(特にCmalpha, Cmq, Cnrは必ず負)
  4. Cmqは絶対必須(省略するとシミュレーション発散)
  5. 推奨値(ArduPilot Rascal実証値)から始めるのが安全

次のステップ:


参照資料#

本記事の執筆にあたり、以下の資料を参照しました [@jsbsim_refman_2024; @jsbsim_docs_2025; @stevens_lewis_2003; @ardupilot_rascal_2025; @xmlgen_github_main_2025]。


関連記事#


© 2025 Yaaasoh. All Rights Reserved.