mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
15823d9e97
Since the RC switches only respond to changes, there is no longer a need for this lock state. The gear can be retracted or deployed by RC switch, flight mode, or mavlink command freely without convoluted unlocking methods. Also removed use of this in the associated Copter code.
32 lines
1.1 KiB
C++
32 lines
1.1 KiB
C++
#include "Copter.h"
|
|
|
|
|
|
// Run landing gear controller at 10Hz
|
|
void Copter::landinggear_update()
|
|
{
|
|
// exit immediately if no landing gear output has been enabled
|
|
if (!SRV_Channels::function_assigned(SRV_Channel::k_landing_gear_control)) {
|
|
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 (flightmode->landing_gear_should_be_deployed()) {
|
|
landinggear.set_position(AP_LandingGear::LandingGear_Deploy);
|
|
}
|
|
|
|
// 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();
|
|
}
|