mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_LandingGear: Helper for landing
This commit is contained in:
parent
2c8d96145f
commit
9cba4b2e70
@ -198,7 +198,11 @@ void AP_LandingGear::update(float height_above_ground_m)
|
|||||||
|
|
||||||
if (_pin_deployed == -1) {
|
if (_pin_deployed == -1) {
|
||||||
last_gear_event_ms = 0;
|
last_gear_event_ms = 0;
|
||||||
gear_state_current = (_deployed == true ? LG_DEPLOYED : LG_RETRACTED);
|
|
||||||
|
// If there was no pilot input and state is still unknown - leave it as it is
|
||||||
|
if (gear_state_current != LG_UNKNOWN) {
|
||||||
|
gear_state_current = (_deployed == true ? LG_DEPLOYED : LG_RETRACTED);
|
||||||
|
}
|
||||||
} else {
|
} else {
|
||||||
LG_LandingGear_State gear_state_new;
|
LG_LandingGear_State gear_state_new;
|
||||||
|
|
||||||
@ -250,3 +254,14 @@ void AP_LandingGear::log_wow_state(LG_WOW_State state)
|
|||||||
AP_HAL::micros64(),
|
AP_HAL::micros64(),
|
||||||
(int8_t)gear_state_current, (int8_t)state);
|
(int8_t)gear_state_current, (int8_t)state);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool AP_LandingGear::check_before_land(void)
|
||||||
|
{
|
||||||
|
// If the landing gear state is not known (most probably as it is not used)
|
||||||
|
if (get_state() == LG_UNKNOWN) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
// If the landing gear was not used - return true, otherwise - check for deployed
|
||||||
|
return (get_state() == LG_DEPLOYED);
|
||||||
|
}
|
||||||
|
@ -83,6 +83,8 @@ public:
|
|||||||
|
|
||||||
void update(float height_above_ground_m);
|
void update(float height_above_ground_m);
|
||||||
|
|
||||||
|
bool check_before_land(void);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
// Parameters
|
// Parameters
|
||||||
AP_Int8 _startup_behaviour; // start-up behaviour (see LandingGearStartupBehaviour)
|
AP_Int8 _startup_behaviour; // start-up behaviour (see LandingGearStartupBehaviour)
|
||||||
|
Loading…
Reference in New Issue
Block a user