Skip to content

Commit 80277e6

Browse files
WickedShelltridge
authored andcommitted
ArduPlane: Add a stall speed parameter
1 parent 5005809 commit 80277e6

File tree

2 files changed

+9
-0
lines changed

2 files changed

+9
-0
lines changed

ArduPlane/Parameters.cpp

+8
Original file line numberDiff line numberDiff line change
@@ -296,6 +296,14 @@ const AP_Param::Info Plane::var_info[] = {
296296
// @User: Standard
297297
ASCALAR(airspeed_max, "AIRSPEED_MAX", AIRSPEED_FBW_MAX),
298298

299+
// @Param: AIRSPEED_STALL
300+
// @DisplayName: Stall airspeed
301+
// @Description: If stall prevention is enabled this speed is used to calculate the minimum airspeed while banking. If this is set to 0 then the stall speed is assumed to be the minimum airspeed speed. Typically set slightly higher then true stall speed. Value is as an indicated (calibrated/apparent) airspeed.
302+
// @Units: m/s
303+
// @Range: 5 75
304+
// @User: Standard
305+
ASCALAR(airspeed_stall, "AIRSPEED_STALL", 0),
306+
299307
// @Param: FBWB_ELEV_REV
300308
// @DisplayName: Fly By Wire elevator reverse
301309
// @Description: Reverse sense of elevator in FBWB and CRUISE modes. When set to 0 up elevator (pulling back on the stick) means to lower altitude. When set to 1, up elevator means to raise altitude.

ArduPlane/Parameters.h

+1
Original file line numberDiff line numberDiff line change
@@ -343,6 +343,7 @@ class Parameters {
343343

344344
k_param_mixing_offset,
345345
k_param_dspoiler_rud_rate,
346+
k_param_airspeed_stall,
346347

347348
k_param_logger = 253, // Logging Group
348349

0 commit comments

Comments
 (0)