ardupilot/Tools/autotest/models/Callisto.json

59 lines
1.4 KiB
JSON

# Callisto model, see https://www.freespaceoperations.com.au/
{
# total vehicle mass
"mass" : 32.5,
# vehicle diameter
"diagonal_size" : 1.325,
# the ref parameters should be taken from a test
# with the copter flying at constant speed in zero wind. This is used
# to estimate the drag coefficient
"refSpd" : 14.88, # m/s
"refAngle" : 8.91, # degrees
"refVoltage" : 46.9, # volts
"refCurrent" : 65.36, # Amps
"refAlt" : 26, # meters AMSL
"refTempC" : 25, # degrees C
"refBatRes" : 0.024, # BAT.Res from log
# full battery voltage
"maxVoltage" : 50.4,
# full battery capacity, Ah
"battCapacityAh" : 44,
# MOT_THST_EXPO
"propExpo" : 0.5,
# approximage maximum yaw rate in deg/sec
"refRotRate" : 120,
# hover throttle from 0 to 1
"hoverThrOut" : 0.36,
# MOT_PWM_MIN
"pwmMin" : 1000,
# MOT_PWM_MAX
"pwmMax" : 1940,
# MOT_SPIN_MIN
"spin_min" : 0.2,
# MOT_SPIN_MAX
"spin_max" : 0.975,
# maximum motor slew rate, or zero to disable
"slew_max" : 75,
# total effective disc area in sq m for 4 x 30 inch diameter rotors
# coaxial rotors count as a single rotor for this parameter)
"disc_area" : 1.82,
# momentum drag coefficient
# ratio of momentum drag realtive to a ducted rotor of the same effective disc area
"mdrag_coef" : 0.10
}