Skip to content

Commit

Permalink
Merge pull request ArduPilot#33 from krausaerospace/k1000_sitl_model
Browse files Browse the repository at this point in the history
Added Sam's K1000 SITL frame
  • Loading branch information
samuelctabor committed Jan 13, 2022
2 parents 8d562bf + a809b88 commit 27f2428
Show file tree
Hide file tree
Showing 4 changed files with 118 additions and 0 deletions.
1 change: 1 addition & 0 deletions Tools/autotest/arduplane.py
Original file line number Diff line number Diff line change
Expand Up @@ -2897,6 +2897,7 @@ def fly_each_frame(self):
"quadplane-cl84": "falls out of sky instead of transitioning",
"quadplane-tilttri": "falls out of sky instead of transitioning",
"quadplane-tilttrivec": "loses attitude control and crashes",
"plane-soaring-k1000": "correctly fails due to no landing WP",
}
for frame in sorted(vinfo_options["frames"].keys()):
self.start_subtest("Testing frame (%s)" % str(frame))
Expand Down
99 changes: 99 additions & 0 deletions Tools/autotest/default_params/plane-soaring-k1000.parm
Original file line number Diff line number Diff line change
@@ -0,0 +1,99 @@
ALT_HOLD_RTL 20000
ARMING_MIS_ITEMS 13
ARMING_RUDDER 0
ARSPD_FBW_MAX 20
ARSPD_FBW_MIN 13
ARSPD_USE 1
BATT2_MONITOR 21
BATT3_MONITOR 21
BATT4_MONITOR 21
BATT5_MONITOR 21
BATT_CAPACITY 56800
BATT_MONITOR 8
BATT_OPTIONS 1
FBWB_CLIMB_RATE 1.75
FENCE_ACTION 0
FENCE_AUTOENABLE 2
FENCE_ALT_MAX 3657
FLTMODE1 10
FLTMODE2 10
FLTMODE_CH 7
FS_GCS_ENABL 1
FS_LONG_ACTN 1
FS_LONG_TIMEOUT 1200
KFF_THR2PTCH 4
LAND_ABORT_THR 1
LAND_DISARMDELAY 3
LAND_FLARE_ALT 2
LAND_FLARE_SEC 0
LAND_PITCH_CD -200
LAND_SLOPE_RCALC 0
LAND_THEN_NEUTRL 1
LAND_THR_SLEW 126
LIM_PITCH_MAX 1000
LIM_PITCH_MIN -2000
LIM_ROLL_CD 3000
LOG_DISARMED 1
LOG_FILE_DSRMROT 1
PTCH2SRV_RMAX_DN 40
PTCH2SRV_RMAX_UP 40
PTCH2SRV_TCONST 0.6
PTCH_RATE_D 0.1021
PTCH_RATE_FF 0.0
PTCH_RATE_I 0.07
PTCH_RATE_P 1.7017
RCMAP_PITCH 3
RCMAP_ROLL 2
RCMAP_THROTTLE 1
RC_OPTIONS 0
RLL_RATE_D 0.1547
RLL_RATE_FF 0.0
RLL_RATE_I 0.1158
RLL_RATE_P 2.5777
RNGFND1_GNDCLEAR 20
RNGFND1_MAX_CM 9500
RNGFND1_MIN_CM 0
RNGFND1_SCALING 1
RNGFND1_SCALING 12.12
RNGFND1_PIN 0
RNGFND1_TYPE 1
RNGFND_LANDING 1
RTL_AUTOLAND 2
RTL_RADIUS 200
SIM_THML_SCENARI 4.00
SIM_BATT_VOLTAGE 25.2
STAB_PITCH_DOWN 0
STICK_MIXING 0
TECS_APPR_SMAX 3
TECS_CLMB_MAX 1.75
TECS_CLMB_OPER 1.5
TECS_INTEG_GAIN 0.01
TECS_LAND_ARSPD 15
TECS_LAND_PDAMP 0.5
TECS_LAND_SINK 0.3
TECS_PITCH_MAX 10
TECS_PTCH_DAMP 0.2
TECS_PTCH_FF_V0 15
TECS_RLL2THR 0
TECS_SINK_MAX 2
TECS_SINK_MIN 0.8
TECS_SINK_OPER 2
TECS_SPDWEIGHT 2
TECS_TCONST_STE 0
TECS_VERT_ACC 15
THROTTLE_NUDGE 0
THR_FAILSAFE 0
TKOFF_GND_PITCH -6.5
TKOFF_LVL_ALT 15
TKOFF_LVL_PITCH 4
TKOFF_ROTATE_SPD 13.5
TKOFF_THR_MAX 100
TKOFF_THR_SLEW 50
TRIM_ARSPD_CM 1500
TRIM_THROTTLE 51
USE_REV_THRUST 0
WP_LOITER_RAD 250
WP_RADIUS 50
YAW2SRV_DAMP 2
YAW2SRV_INT 1
YAW2SRV_SLIP 6
4 changes: 4 additions & 0 deletions Tools/autotest/pysim/vehicleinfo.py
Original file line number Diff line number Diff line change
Expand Up @@ -266,6 +266,10 @@ def __init__(self):
"waf_target": "bin/arduplane",
"default_params_filename": ["default_params/plane.parm", "default_params/plane-soaring.parm"]
},
"plane-soaring-k1000": {
"waf_target": "bin/arduplane",
"default_params_filename": ["default_params/plane.parm","default_params/plane-soaring-k1000.parm"]
},
"gazebo-zephyr": {
"waf_target": "bin/arduplane",
"default_params_filename": "default_params/gazebo-zephyr.parm",
Expand Down
14 changes: 14 additions & 0 deletions libraries/SITL/SIM_Plane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -89,6 +89,20 @@ Plane::Plane(const char *frame_str) :
mass = 2.0;
coefficient.c_drag_p = 0.05;
}

if (strstr(frame_str, "-k1000")) {
mass = 13.8;
coefficient.c_drag_p = 0.0164;
coefficient.s = 1.67;
coefficient.b = 5.0;
coefficient.c = 0.36;
coefficient.oswald = 0.66;
thrust_scale = 100;
have_launcher = true;
launch_accel = 2;
launch_time = 15;
reverse_thrust = true;
}
}

/*
Expand Down

0 comments on commit 27f2428

Please sign in to comment.