Path: blob/master/Tools/autotest/models/skywalker_2013.json
4232 views
# This is an example plane coeffient file used in Ardupilot SITL.1# This allows ArduPilot developers to change SITL plane aerodynamic properties2# without having to change the hard-coded source code values directly.34# These coefficients are from last_letter skywalker_2013/aerodynamics.yaml.5# Thanks to Georacer!67{8"s": 0.45,9"b": 1.88,10"c": 0.24,11"c_lift_0": 0.56,12"c_lift_deltae": 0,13"c_lift_a": 6.9,14"c_lift_q": 0,15"mcoeff": 50,16"oswald": 0.9,17"alpha_stall": 0.4712,18"c_drag_q": 0,19"c_drag_deltae": 0.0,20"c_drag_p": 0.1,21"c_y_0": 0,22"c_y_b": -0.98,23"c_y_p": 0,24"c_y_r": 0,25"c_y_deltaa": 0,26"c_y_deltar": -0.2,27"c_l_0": 0,28"c_l_p": -1.0,29"c_l_b": -0.12,30"c_l_r": 0.14,31"c_l_deltaa": 0.25,32"c_l_deltar": -0.037,33"c_m_0": 0.045,34"c_m_a": -0.7,35"c_m_q": -20,36"c_m_deltae": 1.0,37"c_n_0": 0,38"c_n_b": 0.25,39"c_n_p": 0.022,40"c_n_r": -1,41"c_n_deltaa": 0.00,42"c_n_deltar": 0.1,43"deltaa_max": 0.3491,44"deltae_max": 0.3491,45"deltar_max": 0.3491,4647# The X CoG offset should be -0.02, but that makes the plane too tail heavy48# in manual flight. Adjusted to -0.15 gives reasonable flight.49# CGOffset is in X,Y,Z.50"CGOffset": [51-0.15,520.0,53-0.0554]55}565758