From 73f3b50e2f4469839d6411dabfc3f93fafe9a709 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 17 Nov 2014 16:18:51 -0800 Subject: [PATCH] RC_Channel: make get_control_mid const --- libraries/RC_Channel/RC_Channel.cpp | 2 +- libraries/RC_Channel/RC_Channel.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index 3de5f72684..4c801285ed 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -230,7 +230,7 @@ RC_Channel::calc_pwm(void) used for thr_mid in copter */ int16_t -RC_Channel::get_control_mid() { +RC_Channel::get_control_mid() const { if (_type == RC_CHANNEL_TYPE_RANGE) { int16_t r_in = (radio_min.get()+radio_max.get())/2; diff --git a/libraries/RC_Channel/RC_Channel.h b/libraries/RC_Channel/RC_Channel.h index 16a34c104d..1224603a1e 100644 --- a/libraries/RC_Channel/RC_Channel.h +++ b/libraries/RC_Channel/RC_Channel.h @@ -62,7 +62,7 @@ public: uint8_t get_ch_out(void) const { return _ch_out; }; // get the center stick position expressed as a control_in value - int16_t get_control_mid(); + int16_t get_control_mid() const; // read input from APM_RC - create a control_in value void set_pwm(int16_t pwm);