From ef6a34a9f07b50107d48e327a7ed8d2d73e785e7 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 25 Nov 2019 12:52:18 +1100 Subject: [PATCH] AP_Motors: use enum-class for SRV_CHANNEL_LIMIT_TRIM and friends --- libraries/AP_Motors/AP_MotorsHeli_Dual.cpp | 4 ++-- libraries/AP_Motors/AP_MotorsHeli_Quad.cpp | 4 ++-- libraries/AP_Motors/AP_MotorsHeli_Single.cpp | 4 ++-- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp b/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp index e6ce52841f..8ee045708a 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp @@ -451,10 +451,10 @@ void AP_MotorsHeli_Dual::update_motor_control(RotorControlState state) if (state == ROTOR_CONTROL_STOP) { // set engine run enable aux output to not run position to kill engine when disarmed - SRV_Channels::set_output_limit(SRV_Channel::k_engine_run_enable, SRV_Channel::SRV_CHANNEL_LIMIT_MIN); + SRV_Channels::set_output_limit(SRV_Channel::k_engine_run_enable, SRV_Channel::Limit::MIN); } else { // else if armed, set engine run enable output to run position - SRV_Channels::set_output_limit(SRV_Channel::k_engine_run_enable, SRV_Channel::SRV_CHANNEL_LIMIT_MAX); + SRV_Channels::set_output_limit(SRV_Channel::k_engine_run_enable, SRV_Channel::Limit::MAX); } // Check if rotors are run-up diff --git a/libraries/AP_Motors/AP_MotorsHeli_Quad.cpp b/libraries/AP_Motors/AP_MotorsHeli_Quad.cpp index 1104d69b17..c69c5a5f14 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Quad.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Quad.cpp @@ -186,10 +186,10 @@ void AP_MotorsHeli_Quad::update_motor_control(RotorControlState state) if (state == ROTOR_CONTROL_STOP) { // set engine run enable aux output to not run position to kill engine when disarmed - SRV_Channels::set_output_limit(SRV_Channel::k_engine_run_enable, SRV_Channel::SRV_CHANNEL_LIMIT_MIN); + SRV_Channels::set_output_limit(SRV_Channel::k_engine_run_enable, SRV_Channel::Limit::MIN); } else { // else if armed, set engine run enable output to run position - SRV_Channels::set_output_limit(SRV_Channel::k_engine_run_enable, SRV_Channel::SRV_CHANNEL_LIMIT_MAX); + SRV_Channels::set_output_limit(SRV_Channel::k_engine_run_enable, SRV_Channel::Limit::MAX); } // Check if rotors are run-up diff --git a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp index 24989d2f10..110847f025 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp @@ -354,10 +354,10 @@ void AP_MotorsHeli_Single::update_motor_control(RotorControlState state) if (state == ROTOR_CONTROL_STOP){ // set engine run enable aux output to not run position to kill engine when disarmed - SRV_Channels::set_output_limit(SRV_Channel::k_engine_run_enable, SRV_Channel::SRV_CHANNEL_LIMIT_MIN); + SRV_Channels::set_output_limit(SRV_Channel::k_engine_run_enable, SRV_Channel::Limit::MIN); } else { // else if armed, set engine run enable output to run position - SRV_Channels::set_output_limit(SRV_Channel::k_engine_run_enable, SRV_Channel::SRV_CHANNEL_LIMIT_MAX); + SRV_Channels::set_output_limit(SRV_Channel::k_engine_run_enable, SRV_Channel::Limit::MAX); } // Check if both rotors are run-up, tail rotor controller always returns true if not enabled