Browse Source

RC_Channel: make get_control_mid const

master
Randy Mackay 10 years ago
parent
commit
73f3b50e2f
  1. 2
      libraries/RC_Channel/RC_Channel.cpp
  2. 2
      libraries/RC_Channel/RC_Channel.h

2
libraries/RC_Channel/RC_Channel.cpp

@ -230,7 +230,7 @@ RC_Channel::calc_pwm(void) @@ -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;

2
libraries/RC_Channel/RC_Channel.h

@ -62,7 +62,7 @@ public: @@ -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);

Loading…
Cancel
Save