diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 62898a6649..9a5226a16d 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1545,29 +1545,5 @@ static void tuning(){ } } -// Run landing gear controller at 10Hz -static void landinggear_update(){ - - // If landing gear control is active, run update function. - if (g.ch7_option == AUX_SWITCH_LANDING_GEAR || g.ch8_option == AUX_SWITCH_LANDING_GEAR){ - - // last status (deployed or retracted) used to check for changes - static bool last_deploy_status; - - landinggear.update(); - - // 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(); - } -} - AP_HAL_MAIN(); diff --git a/ArduCopter/LandingGear.pde b/ArduCopter/LandingGear.pde new file mode 100644 index 0000000000..24c78b2b1a --- /dev/null +++ b/ArduCopter/LandingGear.pde @@ -0,0 +1,26 @@ +/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- + +// Run landing gear controller at 10Hz +static void landinggear_update(){ + + // If landing gear control is active, run update function. + if (g.ch7_option == AUX_SWITCH_LANDING_GEAR || g.ch8_option == AUX_SWITCH_LANDING_GEAR){ + + // last status (deployed or retracted) used to check for changes + static bool last_deploy_status; + + landinggear.update(); + + // 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(); + } +} +