mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Plane: adjust target_airspeed with and without airspeed sensor (pitot)
This commit is contained in:
parent
2a0476483b
commit
25dfb583d5
@ -99,7 +99,7 @@ void Plane::calc_airspeed_errors()
|
|||||||
}
|
}
|
||||||
|
|
||||||
// Landing airspeed target
|
// Landing airspeed target
|
||||||
if (control_mode == AUTO && ahrs.airspeed_sensor_enabled()) {
|
if (control_mode == AUTO) {
|
||||||
float land_airspeed = SpdHgt_Controller->get_land_airspeed();
|
float land_airspeed = SpdHgt_Controller->get_land_airspeed();
|
||||||
switch (flight_stage) {
|
switch (flight_stage) {
|
||||||
case AP_SpdHgtControl::FLIGHT_LAND_APPROACH:
|
case AP_SpdHgtControl::FLIGHT_LAND_APPROACH:
|
||||||
|
Loading…
Reference in New Issue
Block a user