AP_HAL_Empty: do not use ch as its used by ChibiOS globally

This commit is contained in:
Siddharth Purohit 2018-05-02 18:25:28 +05:30 committed by Andrew Tridgell
parent 9a2eea9769
commit 2341719929
2 changed files with 7 additions and 7 deletions

View File

@ -16,8 +16,8 @@ uint8_t RCInput::num_channels() {
return 0;
}
uint16_t RCInput::read(uint8_t ch) {
if (ch == 2) return 900; /* throttle should be low, for safety */
uint16_t RCInput::read(uint8_t chan) {
if (chan == 2) return 900; /* throttle should be low, for safety */
else return 1500;
}

View File

@ -7,20 +7,20 @@ void RCOutput::init() {}
void RCOutput::set_freq(uint32_t chmask, uint16_t freq_hz) {}
uint16_t RCOutput::get_freq(uint8_t ch) {
uint16_t RCOutput::get_freq(uint8_t chan) {
return 50;
}
void RCOutput::enable_ch(uint8_t ch)
void RCOutput::enable_ch(uint8_t chan)
{}
void RCOutput::disable_ch(uint8_t ch)
void RCOutput::disable_ch(uint8_t chan)
{}
void RCOutput::write(uint8_t ch, uint16_t period_us)
void RCOutput::write(uint8_t chan, uint16_t period_us)
{}
uint16_t RCOutput::read(uint8_t ch) {
uint16_t RCOutput::read(uint8_t chan) {
return 900;
}