Skip to content

Commit 5cd727c

Browse files
committed
AP_TECS: Corrected formula for _TASmin according to fix in formula for the load factor
See details here: ArduPilot#24320
1 parent 781b086 commit 5cd727c

File tree

1 file changed

+7
-1
lines changed

1 file changed

+7
-1
lines changed

libraries/AP_TECS/AP_TECS.cpp

+7-1
Original file line numberDiff line numberDiff line change
@@ -415,7 +415,13 @@ void AP_TECS::_update_speed(float DT)
415415
if (aparm.stall_prevention) {
416416
// when stall prevention is active we raise the minimum
417417
// airspeed based on aerodynamic load factor
418-
_TASmin *= _load_factor;
418+
/*
419+
As load factor formula fixed in ArduPlane Plane::update_load_factor,
420+
here also should be changes done according to comments by Peter Hall
421+
see issue #24320 [https://github.com/ArduPilot/ardupilot/issues/24320].
422+
*/
423+
424+
_TASmin *= safe_sqrt(_load_factor);
419425
}
420426

421427
if (_TASmax < _TASmin) {

0 commit comments

Comments
 (0)