mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-09 01:13:57 -04:00
Copter: landinggear_update formatting change
no functional change
This commit is contained in:
parent
106c1b4fde
commit
5a664bc348
@ -4,30 +4,31 @@
|
|||||||
// Run landing gear controller at 10Hz
|
// Run landing gear controller at 10Hz
|
||||||
void Copter::landinggear_update()
|
void Copter::landinggear_update()
|
||||||
{
|
{
|
||||||
// If landing gear control is active, run update function.
|
// exit immediately if no landing gear switch is enabled
|
||||||
if (check_if_auxsw_mode_used(AUXSW_LANDING_GEAR)){
|
if (!check_if_auxsw_mode_used(AUXSW_LANDING_GEAR)) {
|
||||||
|
return;
|
||||||
// last status (deployed or retracted) used to check for changes, initialised to startup state of landing gear
|
|
||||||
static bool last_deploy_status = landinggear.deployed();
|
|
||||||
|
|
||||||
// if we are doing an automatic landing procedure, force the landing gear to deploy.
|
|
||||||
// To-Do: should we pause the auto-land procedure to give time for gear to come down?
|
|
||||||
if (control_mode == LAND ||
|
|
||||||
(control_mode == RTL && (rtl_state == RTL_LoiterAtHome || rtl_state == RTL_Land || rtl_state == RTL_FinalDescent)) ||
|
|
||||||
(control_mode == AUTO && auto_mode == Auto_Land) ||
|
|
||||||
(control_mode == AUTO && auto_mode == Auto_RTL && (rtl_state == RTL_LoiterAtHome || rtl_state == RTL_Land || rtl_state == RTL_FinalDescent))) {
|
|
||||||
landinggear.set_position(AP_LandingGear::LandingGear_Deploy_And_Keep_Deployed);
|
|
||||||
}
|
|
||||||
|
|
||||||
// send event message to datalog if status has changed
|
|
||||||
if (landinggear.deployed() != last_deploy_status){
|
|
||||||
if (landinggear.deployed()) {
|
|
||||||
Log_Write_Event(DATA_LANDING_GEAR_DEPLOYED);
|
|
||||||
} else {
|
|
||||||
Log_Write_Event(DATA_LANDING_GEAR_RETRACTED);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
last_deploy_status = landinggear.deployed();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// last status (deployed or retracted) used to check for changes, initialised to startup state of landing gear
|
||||||
|
static bool last_deploy_status = landinggear.deployed();
|
||||||
|
|
||||||
|
// if we are doing an automatic landing procedure, force the landing gear to deploy.
|
||||||
|
// To-Do: should we pause the auto-land procedure to give time for gear to come down?
|
||||||
|
if (control_mode == LAND ||
|
||||||
|
(control_mode == RTL && (rtl_state == RTL_LoiterAtHome || rtl_state == RTL_Land || rtl_state == RTL_FinalDescent)) ||
|
||||||
|
(control_mode == AUTO && auto_mode == Auto_Land) ||
|
||||||
|
(control_mode == AUTO && auto_mode == Auto_RTL && (rtl_state == RTL_LoiterAtHome || rtl_state == RTL_Land || rtl_state == RTL_FinalDescent))) {
|
||||||
|
landinggear.set_position(AP_LandingGear::LandingGear_Deploy_And_Keep_Deployed);
|
||||||
|
}
|
||||||
|
|
||||||
|
// send event message to datalog if status has changed
|
||||||
|
if (landinggear.deployed() != last_deploy_status) {
|
||||||
|
if (landinggear.deployed()) {
|
||||||
|
Log_Write_Event(DATA_LANDING_GEAR_DEPLOYED);
|
||||||
|
} else {
|
||||||
|
Log_Write_Event(DATA_LANDING_GEAR_RETRACTED);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
last_deploy_status = landinggear.deployed();
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user