AP_LandingGear: use enum-class for SRV_CHANNEL_LIMIT_TRIM and friends

This commit is contained in:
Peter Barker 2019-11-25 12:52:18 +11:00 committed by Andrew Tridgell
parent 48def9b8a4
commit 992f216cc5
1 changed files with 2 additions and 2 deletions

View File

@ -120,7 +120,7 @@ void AP_LandingGear::set_position(LandingGearCommand cmd)
void AP_LandingGear::deploy() void AP_LandingGear::deploy()
{ {
// set servo PWM to deployed position // set servo PWM to deployed position
SRV_Channels::set_output_limit(SRV_Channel::k_landing_gear_control, SRV_Channel::SRV_CHANNEL_LIMIT_MAX); SRV_Channels::set_output_limit(SRV_Channel::k_landing_gear_control, SRV_Channel::Limit::MAX);
// set deployed flag // set deployed flag
_deployed = true; _deployed = true;
@ -136,7 +136,7 @@ void AP_LandingGear::deploy()
void AP_LandingGear::retract() void AP_LandingGear::retract()
{ {
// set servo PWM to retracted position // set servo PWM to retracted position
SRV_Channels::set_output_limit(SRV_Channel::k_landing_gear_control, SRV_Channel::SRV_CHANNEL_LIMIT_MIN); SRV_Channels::set_output_limit(SRV_Channel::k_landing_gear_control, SRV_Channel::Limit::MIN);
// reset deployed flag // reset deployed flag
_deployed = false; _deployed = false;