From 23417199291dbaa49dc3c7e08c5e18497f729f73 Mon Sep 17 00:00:00 2001 From: Siddharth Purohit Date: Wed, 2 May 2018 18:25:28 +0530 Subject: [PATCH] AP_HAL_Empty: do not use ch as its used by ChibiOS globally --- libraries/AP_HAL_Empty/RCInput.cpp | 4 ++-- libraries/AP_HAL_Empty/RCOutput.cpp | 10 +++++----- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/libraries/AP_HAL_Empty/RCInput.cpp b/libraries/AP_HAL_Empty/RCInput.cpp index ce620c8c58..05eb521e6b 100644 --- a/libraries/AP_HAL_Empty/RCInput.cpp +++ b/libraries/AP_HAL_Empty/RCInput.cpp @@ -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; } diff --git a/libraries/AP_HAL_Empty/RCOutput.cpp b/libraries/AP_HAL_Empty/RCOutput.cpp index df144663c9..e83047bd3e 100644 --- a/libraries/AP_HAL_Empty/RCOutput.cpp +++ b/libraries/AP_HAL_Empty/RCOutput.cpp @@ -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; }