ardupilot/ArduCopter/landing_gear.cpp

50 lines
1.6 KiB
C++
Raw Permalink Normal View History

#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;
}
2015-01-06 22:51:06 -04:00
// last status (deployed or retracted) used to check for changes, initialised to startup state of landing gear
static bool last_deploy_status = landinggear.deployed();
2015-01-06 22:51:06 -04:00
// 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();
// support height based triggering using rangefinder or altitude above ground
int32_t height_cm = flightmode->get_alt_above_ground_cm();
// use rangefinder if available
switch (rangefinder.status_orient(ROTATION_PITCH_270)) {
case RangeFinder::RangeFinder_NotConnected:
case RangeFinder::RangeFinder_NoData:
// use altitude above home for non-functioning rangefinder
break;
case RangeFinder::RangeFinder_OutOfRangeLow:
// altitude is close to zero (gear should deploy)
height_cm = 0;
break;
case RangeFinder::RangeFinder_OutOfRangeHigh:
case RangeFinder::RangeFinder_Good:
// use last good reading
height_cm = rangefinder_state.alt_cm_filt.get();
break;
}
landinggear.update(height_cm * 0.01f); // convert cm->m for update call
}