From d27cd19daa9156e0d98b91e588c0494b7ce6466a Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Thu, 7 Feb 2019 00:00:36 -0700 Subject: [PATCH] AP_RPM: instance range should use define instead of hardcoded value --- libraries/AP_RPM/RPM_Backend.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_RPM/RPM_Backend.h b/libraries/AP_RPM/RPM_Backend.h index d267b38b46..fee8d9719b 100644 --- a/libraries/AP_RPM/RPM_Backend.h +++ b/libraries/AP_RPM/RPM_Backend.h @@ -32,7 +32,7 @@ public: virtual void update() = 0; int8_t get_pin(void) const { - if (state.instance > 1) { + if (state.instance >= RPM_MAX_INSTANCES) { return -1; } return ap_rpm._pin[state.instance].get();