mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_LandingGear: add OPTIONS param to auto deploy and retract
This commit is contained in:
parent
cc33c8d116
commit
6297306492
@ -67,6 +67,14 @@ const AP_Param::GroupInfo AP_LandingGear::var_info[] = {
|
|||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("RETRACT_ALT", 8, AP_LandingGear, _retract_alt, 0),
|
AP_GROUPINFO("RETRACT_ALT", 8, AP_LandingGear, _retract_alt, 0),
|
||||||
|
|
||||||
|
// @Param: OPTIONS
|
||||||
|
// @DisplayName: Landing gear auto retract/deploy options
|
||||||
|
// @Description: Options to retract or deploy landing gear in Auto or Guided mode
|
||||||
|
// @Values: 1:Retract after Takeoff, 2:Deploy during Land, 3:Retract after Takeoff AND deploy during Land
|
||||||
|
// @Bitmask: 0:Retract after Takeoff,1:Deploy during Land
|
||||||
|
// @User: Standard
|
||||||
|
AP_GROUPINFO("OPTIONS", 9, AP_LandingGear, _options, 3),
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
@ -272,3 +280,19 @@ bool AP_LandingGear::check_before_land(void)
|
|||||||
// If the landing gear was not used - return true, otherwise - check for deployed
|
// If the landing gear was not used - return true, otherwise - check for deployed
|
||||||
return (get_state() == LG_DEPLOYED);
|
return (get_state() == LG_DEPLOYED);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// retract after takeoff if configured via the OPTIONS parameter
|
||||||
|
void AP_LandingGear::retract_after_takeoff()
|
||||||
|
{
|
||||||
|
if (_options.get() & (uint16_t)Option::RETRACT_AFTER_TAKEOFF) {
|
||||||
|
retract();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// deploy for landing if configured via the OPTIONS parameter
|
||||||
|
void AP_LandingGear::deploy_for_landing()
|
||||||
|
{
|
||||||
|
if (_options.get() & (uint16_t)Option::DEPLOY_DURING_LANDING) {
|
||||||
|
deploy();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
@ -85,6 +85,10 @@ public:
|
|||||||
|
|
||||||
bool check_before_land(void);
|
bool check_before_land(void);
|
||||||
|
|
||||||
|
// retract after takeoff or deploy for landing depending on the OPTIONS parameter
|
||||||
|
void retract_after_takeoff();
|
||||||
|
void deploy_for_landing();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
// Parameters
|
// Parameters
|
||||||
AP_Int8 _startup_behaviour; // start-up behaviour (see LandingGearStartupBehaviour)
|
AP_Int8 _startup_behaviour; // start-up behaviour (see LandingGearStartupBehaviour)
|
||||||
@ -95,6 +99,13 @@ private:
|
|||||||
AP_Int8 _pin_weight_on_wheels_polarity;
|
AP_Int8 _pin_weight_on_wheels_polarity;
|
||||||
AP_Int16 _deploy_alt;
|
AP_Int16 _deploy_alt;
|
||||||
AP_Int16 _retract_alt;
|
AP_Int16 _retract_alt;
|
||||||
|
AP_Int16 _options;
|
||||||
|
|
||||||
|
// bitmask of options
|
||||||
|
enum class Option : uint16_t {
|
||||||
|
RETRACT_AFTER_TAKEOFF = (1U<<0),
|
||||||
|
DEPLOY_DURING_LANDING = (1U<<1)
|
||||||
|
};
|
||||||
|
|
||||||
// internal variables
|
// internal variables
|
||||||
bool _deployed; // true if the landing gear has been deployed, initialized false
|
bool _deployed; // true if the landing gear has been deployed, initialized false
|
||||||
|
Loading…
Reference in New Issue
Block a user