From dcb6e74c3fb876f41867aeae4fac9039f1c48564 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 6 Apr 2019 10:12:25 +1100 Subject: [PATCH] AP_RSSI: make type enum class, remove default clause in type switch --- libraries/AP_RSSI/AP_RSSI.cpp | 40 +++++++++++++---------------------- libraries/AP_RSSI/AP_RSSI.h | 14 ++++++------ 2 files changed, 22 insertions(+), 32 deletions(-) diff --git a/libraries/AP_RSSI/AP_RSSI.cpp b/libraries/AP_RSSI/AP_RSSI.cpp index 00c5267297..d20ad8cc32 100644 --- a/libraries/AP_RSSI/AP_RSSI.cpp +++ b/libraries/AP_RSSI/AP_RSSI.cpp @@ -131,35 +131,25 @@ void AP_RSSI::init() // 0.0 represents weakest signal, 1.0 represents maximum signal. float AP_RSSI::read_receiver_rssi() { - // Default to 0 RSSI - float receiver_rssi = 0.0f; - - switch (rssi_type) { - case RssiType::RSSI_DISABLED: - receiver_rssi = 0.0f; - break; - case RssiType::RSSI_ANALOG_PIN: - receiver_rssi = read_pin_rssi(); - break; - case RssiType::RSSI_RC_CHANNEL_VALUE: - receiver_rssi = read_channel_rssi(); - break; - case RssiType::RSSI_RECEIVER: { + switch (RssiType(rssi_type.get())) { + case RssiType::TYPE_DISABLED: + return 0.0f; + case RssiType::ANALOG_PIN: + return read_pin_rssi(); + case RssiType::RC_CHANNEL_VALUE: + return read_channel_rssi(); + case RssiType::RECEIVER: { int16_t rssi = RC_Channels::get_receiver_rssi(); if (rssi != -1) { - receiver_rssi = rssi / 255.0; + return rssi / 255.0; } - break; + return 0.0f; } - case RssiType::RSSI_PWM_PIN: - receiver_rssi = read_pwm_pin_rssi(); - break; - default : - receiver_rssi = 0.0f; - break; - } - - return receiver_rssi; + case RssiType::PWM_PIN: + return read_pwm_pin_rssi(); + } + // should never get to here + return 0.0f; } // Read the receiver RSSI value as an 8-bit integer diff --git a/libraries/AP_RSSI/AP_RSSI.h b/libraries/AP_RSSI/AP_RSSI.h index 2a99bda1d2..690f5cdbad 100644 --- a/libraries/AP_RSSI/AP_RSSI.h +++ b/libraries/AP_RSSI/AP_RSSI.h @@ -21,12 +21,12 @@ class AP_RSSI { public: - enum RssiType { - RSSI_DISABLED = 0, - RSSI_ANALOG_PIN = 1, - RSSI_RC_CHANNEL_VALUE = 2, - RSSI_RECEIVER = 3, - RSSI_PWM_PIN = 4 + enum class RssiType { + TYPE_DISABLED = 0, + ANALOG_PIN = 1, + RC_CHANNEL_VALUE = 2, + RECEIVER = 3, + PWM_PIN = 4 }; AP_RSSI(); @@ -44,7 +44,7 @@ public: void init(); // return true if rssi reading is enabled - bool enabled() const { return rssi_type != RSSI_DISABLED; } + bool enabled() const { return RssiType(rssi_type.get()) != RssiType::TYPE_DISABLED; } // Read the receiver RSSI value as a float 0.0f - 1.0f. // 0.0 represents weakest signal, 1.0 represents maximum signal.