diff --git a/Tools/autotest/models/freestyle.json b/Tools/autotest/models/freestyle.json new file mode 100644 index 0000000000000..b0556fbedb18c --- /dev/null +++ b/Tools/autotest/models/freestyle.json @@ -0,0 +1,62 @@ +# 5 inch FPV Freestyle/Racing model + +{ + # total vehicle mass in kg + "mass" : 0.8, + + # vehicle diameter + "diagonal_size" : 0.25, + + # 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" : 20.0, # m/s + "refAngle" : 45.0, # degrees + "refVoltage" : 23.2, # volts + "refCurrent" : 5, # Amps + "refAlt" : 607, # meters AMSL + "refTempC" : 25, # degrees C + "refBatRes" : 0.0226, # BAT.Res from log + + # full battery voltage + "maxVoltage" : 25.2, + + # full battery capacity, Ah + # 0 means unlimited + "battCapacityAh" : 0, + + # MOT_THST_EXPO + "propExpo" : 0.7, + + # approximate maximum yaw rate in deg/sec + "refRotRate" : 700, + + # hover throttle from 0 to 1 + "hoverThrOut" : 0.125, + + # MOT_PWM_MIN + "pwmMin" : 1000, + + # MOT_PWM_MAX + "pwmMax" : 2000, + + # MOT_SPIN_MIN + "spin_min" : 0.01, + + # MOT_SPIN_MAX + "spin_max" : 0.95, + + # maximum motor slew rate, or zero to disable + "slew_max" : 0, + + # total effective disc area in sq m for 4 x 5 inch diameter rotors + "disc_area" : 0.204, + + # momentum drag coefficient + # ratio of momentum drag relative to a ducted rotor of the same effective disc area + "mdrag_coef" : 0.10, + + # number of motors + "num_motors" : 4 +} + diff --git a/Tools/autotest/models/freestyle.param b/Tools/autotest/models/freestyle.param new file mode 100644 index 0000000000000..6ab0ddad76446 --- /dev/null +++ b/Tools/autotest/models/freestyle.param @@ -0,0 +1,91 @@ +ACRO_OPTIONS 1.000000 +ACRO_RP_EXPO 0.400000 +ACRO_RP_RATE 533.000000 +ACRO_THR_MID 0.300000 +ACRO_TRAINER 0.000000 +ACRO_Y_EXPO 0.400000 +ACRO_Y_RATE 533.000000 +ANGLE_MAX 7000.000000 +ARMING_RUDDER 0.000000 +ATC_ACCEL_P_MAX 160000.000000 +ATC_ACCEL_R_MAX 160000.000000 +ATC_ACCEL_Y_MAX 120000.000000 +ATC_ANG_PIT_P 15.000000 +ATC_ANG_RLL_P 15.000000 +ATC_ANG_YAW_P 10.000000 +ATC_INPUT_TC 0.040000 +ATC_RAT_PIT_P 0.040000 +ATC_RAT_PIT_I 0.040000 +ATC_RAT_PIT_D 0.001200 +ATC_RAT_PIT_FLTD 60.000000 +ATC_RAT_PIT_FLTE 40.000000 +ATC_RAT_PIT_FLTT 60.000000 +ATC_RAT_PIT_SMAX 50.000000 +ATC_RAT_RLL_P 0.048000 +ATC_RAT_RLL_I 0.048000 +ATC_RAT_RLL_D 0.000800 +ATC_RAT_RLL_FLTD 60.000000 +ATC_RAT_RLL_FLTT 60.000000 +ATC_RAT_RLL_SMAX 50.000000 +ATC_RAT_YAW_P 0.500000 +ATC_RAT_YAW_I 0.050000 +ATC_RAT_YAW_D 0.010000 +ATC_RAT_YAW_FLTD 60.000000 +ATC_RAT_YAW_FLTE 2.000000 +ATC_RAT_YAW_FLTT 60.000000 +ATC_RAT_YAW_SMAX 50.000000 +ATC_SLEW_YAW 24000.000000 +ATC_THR_MIX_MAN 4.000000 +AUTO_OPTIONS 3.000000 +BATT_CAPACITY 1300.000000 +BATT_OPTIONS 64.000000 +CIRCLE_RATE 200.000000 +DISARM_DELAY 0.000000 +EK3_GLITCH_RAD 0.000000 +FLTMODE_CH 0.000000 +FRAME_CLASS 1.000000 +GCS_PID_MASK 7.000000 +INS_ACCEL_FILTER 15.000000 +INS_FAST_SAMPLE 3.000000 +INS_GYRO_FILTER 120.000000 +INS_HNTC2_ATT 60.000000 +INS_HNTC2_BW 10.000000 +INS_HNTC2_ENABLE 1.000000 +INS_HNTC2_FREQ 90.000000 +INS_HNTC2_HMNCS 15.000000 +INS_HNTC2_MODE 3.000000 +INS_HNTC2_OPTS 22.000000 +INS_HNTC2_REF 1.000000 +LAND_ALT_LOW 700.000000 +LOG_BITMASK 196607.000000 +LOG_DARM_RATEMAX 1.000000 +LOIT_SPEED 4000.000000 +LOIT_ACC_MAX 1000.000000 +LOIT_BRK_ACCEL 500.000000 +LOIT_BRK_JERK 1000.000000 +LOIT_BRK_DELAY 0.250000 +MOT_BAT_VOLT_MAX 25.200000 +MOT_BAT_VOLT_MIN 19.800000 +MOT_SPIN_ARM 0.010000 +MOT_SPIN_MIN 0.010000 +MOT_SPOOL_TIME 0.250000 +MOT_THST_EXPO 0.700000 +MOT_THST_HOVER 0.125000 +PILOT_SPEED_DN 500.000000 +PILOT_SPEED_UP 500.000000 +PILOT_Y_RATE 250.000000 +PSC_ACCZ_FLTD 40.000000 +PSC_ACCZ_FLTT 40.000000 +PSC_ACCZ_P 0.200000 +PSC_JERK_XY 10.000000 +PSC_VELZ_P 3.000000 +RC7_OPTION 0.000000 +RTL_ALT 700.000000 +RTL_LOIT_TIME 2000.000000 +RTL_SPEED 900.000000 +WPNAV_ACCEL 1100.000000 +WPNAV_ACCEL_Z 300.000000 +WPNAV_JERK 6.000000 +WPNAV_SPEED 3000.000000 +WPNAV_SPEED_DN 500.000000 +WPNAV_SPEED_UP 500.000000 diff --git a/Tools/autotest/pysim/vehicleinfo.py b/Tools/autotest/pysim/vehicleinfo.py index 198dda7461cae..951e1289b847b 100644 --- a/Tools/autotest/pysim/vehicleinfo.py +++ b/Tools/autotest/pysim/vehicleinfo.py @@ -190,6 +190,12 @@ def __init__(self): "default_params_filename": ["default_params/copter.parm", "default_params/quad-can.parm"], "periph_params_filename": ["default_params/periph.parm", "default_params/quad-periph.parm"], }, + "freestyle": { + "model": "X:@ROMFS/models/freestyle.json", + "waf_target": "bin/arducopter", + "default_params_filename": ["default_params/copter.parm", + "models/freestyle.param"], + }, }, }, "Helicopter": {