diff --git a/libraries/RC/APM2_RC.cpp b/libraries/RC/APM2_RC.cpp index 2ec7a762f1..ca56b8b5e0 100644 --- a/libraries/RC/APM2_RC.cpp +++ b/libraries/RC/APM2_RC.cpp @@ -99,7 +99,7 @@ APM2_RC::init() // trim out the radio for(int c = 0; c < 50; c++){ delay(20); - read_pwm(); + read(); } trim(); @@ -109,7 +109,7 @@ APM2_RC::init() } } -void APM2_RC::read_pwm() +void APM2_RC::read() { //Serial.print("ch1 in "); //Serial.print(raw[CH1],DEC); @@ -189,7 +189,7 @@ APM2_RC::trim() { uint8_t temp = _mix_mode; _mix_mode = 0; - read_pwm(); + read(); _mix_mode = temp; // Store the trim values diff --git a/libraries/RC/APM2_RC.h b/libraries/RC/APM2_RC.h index e31c6be90b..c2dd459a97 100644 --- a/libraries/RC/APM2_RC.h +++ b/libraries/RC/APM2_RC.h @@ -10,7 +10,7 @@ class APM2_RC : public RC public: APM2_RC(); void init(); - void read_pwm(); + void read(); void output(); void set_ch_pwm(uint8_t ch, uint16_t pwm); void trim(); diff --git a/libraries/RC/AP_RC.cpp b/libraries/RC/AP_RC.cpp index ccabda5470..9ec742f305 100644 --- a/libraries/RC/AP_RC.cpp +++ b/libraries/RC/AP_RC.cpp @@ -75,7 +75,7 @@ AP_RC::init() // trim out the radio for(int c = 0; c < 50; c++){ delay(20); - read_pwm(); + read(); } trim(); @@ -90,7 +90,7 @@ AP_RC::init() } void -AP_RC::read_pwm() +AP_RC::read() { if((_direction_mask & 1) == 0 ) timer1diff = REVERSE - timer1diff; @@ -163,7 +163,7 @@ AP_RC::trim() { uint8_t temp = _mix_mode; _mix_mode = 0; - read_pwm(); + read(); _mix_mode = temp; radio_trim[CH1] = radio_in[CH1]; diff --git a/libraries/RC/AP_RC.h b/libraries/RC/AP_RC.h index 184ef7e071..ff878fa907 100644 --- a/libraries/RC/AP_RC.h +++ b/libraries/RC/AP_RC.h @@ -10,7 +10,7 @@ class AP_RC : public RC public: AP_RC(); void init(); - void read_pwm(); + void read(); void output(); void set_ch_pwm(uint8_t ch, uint16_t pwm); void trim(); diff --git a/libraries/RC/RC.h b/libraries/RC/RC.h index cb9b0b870c..fdc4505e7d 100644 --- a/libraries/RC/RC.h +++ b/libraries/RC/RC.h @@ -24,7 +24,7 @@ class RC // RC(); virtual void init(); virtual void trim(); - virtual void read_pwm(); + virtual void read(); virtual void output(); virtual void set_channel_direction(uint8_t ch, int8_t dir); virtual void set_ch_pwm(uint8_t ch, uint16_t pwm);