mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
ArduPlane: Fix filename in header
This commit is contained in:
parent
1841313f73
commit
5f5c200625
@ -586,7 +586,8 @@ void Plane::check_short_failsafe()
|
|||||||
flight_stage != AP_SpdHgtControl::FLIGHT_LAND_FINAL &&
|
flight_stage != AP_SpdHgtControl::FLIGHT_LAND_FINAL &&
|
||||||
flight_stage != AP_SpdHgtControl::FLIGHT_LAND_PREFLARE &&
|
flight_stage != AP_SpdHgtControl::FLIGHT_LAND_PREFLARE &&
|
||||||
flight_stage != AP_SpdHgtControl::FLIGHT_LAND_APPROACH) {
|
flight_stage != AP_SpdHgtControl::FLIGHT_LAND_APPROACH) {
|
||||||
if(failsafe.ch3_failsafe) { // The condition is checked and the flag ch3_failsafe is set in radio.pde
|
// The condition is checked and the flag ch3_failsafe is set in radio.cpp
|
||||||
|
if(failsafe.ch3_failsafe) {
|
||||||
failsafe_short_on_event(FAILSAFE_SHORT);
|
failsafe_short_on_event(FAILSAFE_SHORT);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -55,7 +55,7 @@ int8_t Plane::test_radio_pwm(uint8_t argc, const Menu::arg *argv)
|
|||||||
while(1) {
|
while(1) {
|
||||||
hal.scheduler->delay(20);
|
hal.scheduler->delay(20);
|
||||||
|
|
||||||
// Filters radio input - adjust filters in the radio.pde file
|
// Filters radio input - adjust filters in the radio.cpp file
|
||||||
// ----------------------------------------------------------
|
// ----------------------------------------------------------
|
||||||
read_radio();
|
read_radio();
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user