mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_LandingGear: Add force_deploy method.
This commit is contained in:
parent
fd61c3179a
commit
c297aaeeab
@ -59,7 +59,15 @@ void AP_LandingGear::retract()
|
|||||||
|
|
||||||
/// update - should be called at 10hz
|
/// update - should be called at 10hz
|
||||||
void AP_LandingGear::update()
|
void AP_LandingGear::update()
|
||||||
{
|
{
|
||||||
|
// if there is a force deploy active, disable retraction, then reset force deploy to consume it
|
||||||
|
// gear will be deployed automatically because _retract_enabled is false.
|
||||||
|
// this will disable retract switch until it is cycled through deploy position
|
||||||
|
if ( _force_deploy){
|
||||||
|
enable(false);
|
||||||
|
force_deploy(false);
|
||||||
|
}
|
||||||
|
|
||||||
if (!_retract_enabled) {
|
if (!_retract_enabled) {
|
||||||
// force deployment if retract is not enabled
|
// force deployment if retract is not enabled
|
||||||
deploy();
|
deploy();
|
||||||
@ -68,7 +76,7 @@ void AP_LandingGear::update()
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (_command_mode == COMMAND_MODE_DEPLOY){
|
if (_command_mode == COMMAND_MODE_DEPLOY){
|
||||||
deploy();
|
deploy();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -41,6 +41,8 @@ public:
|
|||||||
void update();
|
void update();
|
||||||
|
|
||||||
void set_cmd_mode(int8_t cmd) { _command_mode = cmd; }
|
void set_cmd_mode(int8_t cmd) { _command_mode = cmd; }
|
||||||
|
|
||||||
|
void force_deploy(bool force) { _force_deploy = force;}
|
||||||
|
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
@ -54,6 +56,7 @@ private:
|
|||||||
|
|
||||||
// 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
|
||||||
|
bool _force_deploy; // used by main code to force landing gear to deploy, such as in Land mode
|
||||||
int8_t _command_mode; // pilots commanded control mode: Manual Deploy, Auto, or Manual Retract
|
int8_t _command_mode; // pilots commanded control mode: Manual Deploy, Auto, or Manual Retract
|
||||||
|
|
||||||
/// enable - enable landing gear retraction
|
/// enable - enable landing gear retraction
|
||||||
|
Loading…
Reference in New Issue
Block a user