mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Tools: added Callisto model from Leonard
This commit is contained in:
parent
767773da5e
commit
10a07bf4f9
47
Tools/autotest/models/Callisto.json
Normal file
47
Tools/autotest/models/Callisto.json
Normal file
@ -0,0 +1,47 @@
|
||||
# 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,
|
||||
|
||||
# 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
|
||||
}
|
54
Tools/autotest/models/Callisto.param
Normal file
54
Tools/autotest/models/Callisto.param
Normal file
@ -0,0 +1,54 @@
|
||||
ACRO_YAW_P,2
|
||||
ANGLE_MAX,3000
|
||||
ATC_ACCEL_P_MAX,30000
|
||||
ATC_ACCEL_R_MAX,30000
|
||||
ATC_ACCEL_Y_MAX,6000
|
||||
ATC_ANG_PIT_P,6
|
||||
ATC_ANG_RLL_P,6
|
||||
ATC_ANG_YAW_P,5
|
||||
ATC_INPUT_TC,0.25
|
||||
ATC_RAT_PIT_D,0.0080
|
||||
ATC_RAT_PIT_FLTD,10
|
||||
ATC_RAT_PIT_I,0.1634
|
||||
ATC_RAT_PIT_IMAX,0.5
|
||||
ATC_RAT_PIT_P,0.1634
|
||||
ATC_RAT_RLL_D,0.0085
|
||||
ATC_RAT_RLL_FLTD,10
|
||||
ATC_RAT_RLL_I,0.1671
|
||||
ATC_RAT_RLL_IMAX,0.5
|
||||
ATC_RAT_RLL_P,0.1671
|
||||
ATC_RAT_YAW_I,0.05
|
||||
ATC_RAT_YAW_P,0.5
|
||||
ATC_SLEW_YAW,3000
|
||||
ATC_THR_MIX_MAX,2
|
||||
AUTOTUNE_AGGR,0.1
|
||||
AUTOTUNE_MIN_D,0.001
|
||||
FRAME_CLASS,4
|
||||
FRAME_TYPE,1
|
||||
INS_ACCEL_FILTER,10
|
||||
LOIT_ACC_MAX,457.2916
|
||||
LOIT_ANG_MAX,25
|
||||
MOT_BAT_CURR_TC,2
|
||||
MOT_BAT_VOLT_MAX,50.4
|
||||
MOT_BAT_VOLT_MIN,39.6
|
||||
MOT_HOVER_LEARN,0
|
||||
MOT_PWM_MAX,1940
|
||||
MOT_PWM_MIN,1000
|
||||
MOT_SPIN_ARM,0.16
|
||||
MOT_SPIN_MAX,0.975
|
||||
MOT_SPIN_MIN,0.2
|
||||
MOT_THST_EXPO,0.5
|
||||
MOT_THST_HOVER,0.52
|
||||
MOT_YAW_HEADROOM,50
|
||||
PSC_ACCZ_FLTD,10
|
||||
PSC_ACCZ_FLTE,0
|
||||
PSC_ACCZ_FLTT,10
|
||||
PSC_ACCZ_I,0.5
|
||||
PSC_ACCZ_P,0.25
|
||||
PSC_ANGLE_MAX,45
|
||||
PSC_POSXY_P,1
|
||||
PSC_POSZ_P,0.5
|
||||
PSC_VELZ_P,2.5
|
||||
WPNAV_ACCEL,250
|
||||
WPNAV_SPEED,1500
|
||||
SIM_BATT_VOLTAGE 50
|
Loading…
Reference in New Issue
Block a user