From 992f216cc592428a22575d7fa6cdf1ff75aa6beb Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 25 Nov 2019 12:52:18 +1100 Subject: [PATCH] AP_LandingGear: use enum-class for SRV_CHANNEL_LIMIT_TRIM and friends --- libraries/AP_LandingGear/AP_LandingGear.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_LandingGear/AP_LandingGear.cpp b/libraries/AP_LandingGear/AP_LandingGear.cpp index 45dfc99f54..a6e655a954 100644 --- a/libraries/AP_LandingGear/AP_LandingGear.cpp +++ b/libraries/AP_LandingGear/AP_LandingGear.cpp @@ -120,7 +120,7 @@ void AP_LandingGear::set_position(LandingGearCommand cmd) void AP_LandingGear::deploy() { // 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 _deployed = true; @@ -136,7 +136,7 @@ void AP_LandingGear::deploy() void AP_LandingGear::retract() { // 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 _deployed = false;