diff --git a/libraries/AP_HAL_Empty/AP_HAL_Empty_Namespace.h b/libraries/AP_HAL_Empty/AP_HAL_Empty_Namespace.h index 19d901ddc3..b63060a297 100644 --- a/libraries/AP_HAL_Empty/AP_HAL_Empty_Namespace.h +++ b/libraries/AP_HAL_Empty/AP_HAL_Empty_Namespace.h @@ -1,29 +1,19 @@ - -#ifndef __AP_HAL_EMPTY_NAMESPACE_H__ -#define __AP_HAL_EMPTY_NAMESPACE_H__ - -/* While not strictly required, names inside the Empty namespace are prefixed - * with Empty for clarity. (Some of our users aren't familiar with all of the - * C++ namespace rules.) - */ +#pragma once namespace Empty { - class EmptyUARTDriver; - class EmptyI2CDriver; - class EmptySPIDeviceManager; - class EmptySPIDeviceDriver; - class EmptyAnalogSource; - class EmptyAnalogIn; - class EmptyStorage; - class EmptyGPIO; - class EmptyDigitalSource; - class EmptyRCInput; - class EmptyRCOutput; - class EmptySemaphore; - class EmptyScheduler; - class EmptyUtil; - class EmptyPrivateMember; + class UARTDriver; + class I2CDriver; + class SPIDeviceManager; + class SPIDeviceDriver; + class AnalogSource; + class AnalogIn; + class Storage; + class GPIO; + class DigitalSource; + class RCInput; + class RCOutput; + class Semaphore; + class Scheduler; + class Util; + class PrivateMember; } - -#endif // __AP_HAL_EMPTY_NAMESPACE_H__ - diff --git a/libraries/AP_HAL_Empty/AnalogIn.cpp b/libraries/AP_HAL_Empty/AnalogIn.cpp index ffa8daabcc..9c8ee0b9d7 100644 --- a/libraries/AP_HAL_Empty/AnalogIn.cpp +++ b/libraries/AP_HAL_Empty/AnalogIn.cpp @@ -2,46 +2,46 @@ using namespace Empty; -EmptyAnalogSource::EmptyAnalogSource(float v) : +AnalogSource::AnalogSource(float v) : _v(v) {} -float EmptyAnalogSource::read_average() { +float AnalogSource::read_average() { return _v; } -float EmptyAnalogSource::voltage_average() { +float AnalogSource::voltage_average() { return 5.0f * _v / 1024.0f; } -float EmptyAnalogSource::voltage_latest() { +float AnalogSource::voltage_latest() { return 5.0f * _v / 1024.0f; } -float EmptyAnalogSource::read_latest() { +float AnalogSource::read_latest() { return _v; } -void EmptyAnalogSource::set_pin(uint8_t p) +void AnalogSource::set_pin(uint8_t p) {} -void EmptyAnalogSource::set_stop_pin(uint8_t p) +void AnalogSource::set_stop_pin(uint8_t p) {} -void EmptyAnalogSource::set_settle_time(uint16_t settle_time_ms) +void AnalogSource::set_settle_time(uint16_t settle_time_ms) {} -EmptyAnalogIn::EmptyAnalogIn() +AnalogIn::AnalogIn() {} -void EmptyAnalogIn::init() +void AnalogIn::init() {} -AP_HAL::AnalogSource* EmptyAnalogIn::channel(int16_t n) { - return new EmptyAnalogSource(1.11); +AP_HAL::AnalogSource* AnalogIn::channel(int16_t n) { + return new AnalogSource(1.11); } -float EmptyAnalogIn::board_voltage(void) +float AnalogIn::board_voltage(void) { return 0; } diff --git a/libraries/AP_HAL_Empty/AnalogIn.h b/libraries/AP_HAL_Empty/AnalogIn.h index e53ea8a5b1..160145a306 100644 --- a/libraries/AP_HAL_Empty/AnalogIn.h +++ b/libraries/AP_HAL_Empty/AnalogIn.h @@ -4,9 +4,9 @@ #include "AP_HAL_Empty.h" -class Empty::EmptyAnalogSource : public AP_HAL::AnalogSource { +class Empty::AnalogSource : public AP_HAL::AnalogSource { public: - EmptyAnalogSource(float v); + AnalogSource(float v); float read_average(); float read_latest(); void set_pin(uint8_t p); @@ -19,9 +19,9 @@ private: float _v; }; -class Empty::EmptyAnalogIn : public AP_HAL::AnalogIn { +class Empty::AnalogIn : public AP_HAL::AnalogIn { public: - EmptyAnalogIn(); + AnalogIn(); void init(); AP_HAL::AnalogSource* channel(int16_t n); float board_voltage(void); diff --git a/libraries/AP_HAL_Empty/GPIO.cpp b/libraries/AP_HAL_Empty/GPIO.cpp index e2ab93b11f..862e3772ef 100644 --- a/libraries/AP_HAL_Empty/GPIO.cpp +++ b/libraries/AP_HAL_Empty/GPIO.cpp @@ -3,62 +3,62 @@ using namespace Empty; -EmptyGPIO::EmptyGPIO() +GPIO::GPIO() {} -void EmptyGPIO::init() +void GPIO::init() {} -void EmptyGPIO::pinMode(uint8_t pin, uint8_t output) +void GPIO::pinMode(uint8_t pin, uint8_t output) {} -int8_t EmptyGPIO::analogPinToDigitalPin(uint8_t pin) +int8_t GPIO::analogPinToDigitalPin(uint8_t pin) { return -1; } -uint8_t EmptyGPIO::read(uint8_t pin) { +uint8_t GPIO::read(uint8_t pin) { return 0; } -void EmptyGPIO::write(uint8_t pin, uint8_t value) +void GPIO::write(uint8_t pin, uint8_t value) {} -void EmptyGPIO::toggle(uint8_t pin) +void GPIO::toggle(uint8_t pin) {} /* Alternative interface: */ -AP_HAL::DigitalSource* EmptyGPIO::channel(uint16_t n) { - return new EmptyDigitalSource(0); +AP_HAL::DigitalSource* GPIO::channel(uint16_t n) { + return new DigitalSource(0); } /* Interrupt interface: */ -bool EmptyGPIO::attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p, +bool GPIO::attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p, uint8_t mode) { return true; } -bool EmptyGPIO::usb_connected(void) +bool GPIO::usb_connected(void) { return false; } -EmptyDigitalSource::EmptyDigitalSource(uint8_t v) : +DigitalSource::DigitalSource(uint8_t v) : _v(v) {} -void EmptyDigitalSource::mode(uint8_t output) +void DigitalSource::mode(uint8_t output) {} -uint8_t EmptyDigitalSource::read() { +uint8_t DigitalSource::read() { return _v; } -void EmptyDigitalSource::write(uint8_t value) { +void DigitalSource::write(uint8_t value) { _v = value; } -void EmptyDigitalSource::toggle() { +void DigitalSource::toggle() { _v = !_v; } diff --git a/libraries/AP_HAL_Empty/GPIO.h b/libraries/AP_HAL_Empty/GPIO.h index 1bf209f169..a74841c98b 100644 --- a/libraries/AP_HAL_Empty/GPIO.h +++ b/libraries/AP_HAL_Empty/GPIO.h @@ -4,9 +4,9 @@ #include "AP_HAL_Empty.h" -class Empty::EmptyGPIO : public AP_HAL::GPIO { +class Empty::GPIO : public AP_HAL::GPIO { public: - EmptyGPIO(); + GPIO(); void init(); void pinMode(uint8_t pin, uint8_t output); int8_t analogPinToDigitalPin(uint8_t pin); @@ -25,9 +25,9 @@ public: bool usb_connected(void); }; -class Empty::EmptyDigitalSource : public AP_HAL::DigitalSource { +class Empty::DigitalSource : public AP_HAL::DigitalSource { public: - EmptyDigitalSource(uint8_t v); + DigitalSource(uint8_t v); void mode(uint8_t output); uint8_t read(); void write(uint8_t value); diff --git a/libraries/AP_HAL_Empty/HAL_Empty_Class.cpp b/libraries/AP_HAL_Empty/HAL_Empty_Class.cpp index 6f63796a32..3d76b03d96 100644 --- a/libraries/AP_HAL_Empty/HAL_Empty_Class.cpp +++ b/libraries/AP_HAL_Empty/HAL_Empty_Class.cpp @@ -9,19 +9,19 @@ using namespace Empty; -static EmptyUARTDriver uartADriver; -static EmptyUARTDriver uartBDriver; -static EmptyUARTDriver uartCDriver; -static EmptySemaphore i2cSemaphore; -static EmptyI2CDriver i2cDriver(&i2cSemaphore); -static EmptySPIDeviceManager spiDeviceManager; -static EmptyAnalogIn analogIn; -static EmptyStorage storageDriver; -static EmptyGPIO gpioDriver; -static EmptyRCInput rcinDriver; -static EmptyRCOutput rcoutDriver; -static EmptyScheduler schedulerInstance; -static EmptyUtil utilInstance; +static UARTDriver uartADriver; +static UARTDriver uartBDriver; +static UARTDriver uartCDriver; +static Semaphore i2cSemaphore; +static I2CDriver i2cDriver(&i2cSemaphore); +static SPIDeviceManager spiDeviceManager; +static AnalogIn analogIn; +static Storage storageDriver; +static GPIO gpioDriver; +static RCInput rcinDriver; +static RCOutput rcoutDriver; +static Scheduler schedulerInstance; +static Util utilInstance; HAL_Empty::HAL_Empty() : AP_HAL::HAL( @@ -42,7 +42,7 @@ HAL_Empty::HAL_Empty() : &rcoutDriver, &schedulerInstance, &utilInstance), - _member(new EmptyPrivateMember(123)) + _member(new PrivateMember(123)) {} void HAL_Empty::run(int argc, char* const argv[], Callbacks* callbacks) const diff --git a/libraries/AP_HAL_Empty/HAL_Empty_Class.h b/libraries/AP_HAL_Empty/HAL_Empty_Class.h index ba8d917197..fdc2dc0fad 100644 --- a/libraries/AP_HAL_Empty/HAL_Empty_Class.h +++ b/libraries/AP_HAL_Empty/HAL_Empty_Class.h @@ -10,5 +10,5 @@ public: HAL_Empty(); void run(int argc, char* const* argv, Callbacks* callbacks) const override; private: - Empty::EmptyPrivateMember *_member; + Empty::PrivateMember *_member; }; diff --git a/libraries/AP_HAL_Empty/I2CDriver.cpp b/libraries/AP_HAL_Empty/I2CDriver.cpp index c4f6b8fa83..0411759d8b 100644 --- a/libraries/AP_HAL_Empty/I2CDriver.cpp +++ b/libraries/AP_HAL_Empty/I2CDriver.cpp @@ -4,35 +4,35 @@ using namespace Empty; -void EmptyI2CDriver::begin() {} -void EmptyI2CDriver::end() {} -void EmptyI2CDriver::setTimeout(uint16_t ms) {} -void EmptyI2CDriver::setHighSpeed(bool active) {} +void I2CDriver::begin() {} +void I2CDriver::end() {} +void I2CDriver::setTimeout(uint16_t ms) {} +void I2CDriver::setHighSpeed(bool active) {} -uint8_t EmptyI2CDriver::write(uint8_t addr, uint8_t len, uint8_t* data) +uint8_t I2CDriver::write(uint8_t addr, uint8_t len, uint8_t* data) {return 1;} -uint8_t EmptyI2CDriver::writeRegister(uint8_t addr, uint8_t reg, uint8_t val) +uint8_t I2CDriver::writeRegister(uint8_t addr, uint8_t reg, uint8_t val) {return 1;} -uint8_t EmptyI2CDriver::writeRegisters(uint8_t addr, uint8_t reg, +uint8_t I2CDriver::writeRegisters(uint8_t addr, uint8_t reg, uint8_t len, uint8_t* data) {return 1;} -uint8_t EmptyI2CDriver::read(uint8_t addr, uint8_t len, uint8_t* data) +uint8_t I2CDriver::read(uint8_t addr, uint8_t len, uint8_t* data) { memset(data, 0, len); return 0; } -uint8_t EmptyI2CDriver::readRegister(uint8_t addr, uint8_t reg, uint8_t* data) +uint8_t I2CDriver::readRegister(uint8_t addr, uint8_t reg, uint8_t* data) { *data = 0; return 1; } -uint8_t EmptyI2CDriver::readRegisters(uint8_t addr, uint8_t reg, +uint8_t I2CDriver::readRegisters(uint8_t addr, uint8_t reg, uint8_t len, uint8_t* data) { memset(data, 0, len); return 1; } -uint8_t EmptyI2CDriver::lockup_count() {return 0;} +uint8_t I2CDriver::lockup_count() {return 0;} diff --git a/libraries/AP_HAL_Empty/I2CDriver.h b/libraries/AP_HAL_Empty/I2CDriver.h index 404643760e..efdae9f240 100644 --- a/libraries/AP_HAL_Empty/I2CDriver.h +++ b/libraries/AP_HAL_Empty/I2CDriver.h @@ -4,9 +4,9 @@ #include "AP_HAL_Empty.h" -class Empty::EmptyI2CDriver : public AP_HAL::I2CDriver { +class Empty::I2CDriver : public AP_HAL::I2CDriver { public: - EmptyI2CDriver(AP_HAL::Semaphore* semaphore) : _semaphore(semaphore) {} + I2CDriver(AP_HAL::Semaphore* semaphore) : _semaphore(semaphore) {} void begin(); void end(); void setTimeout(uint16_t ms); diff --git a/libraries/AP_HAL_Empty/PrivateMember.cpp b/libraries/AP_HAL_Empty/PrivateMember.cpp index 08761b01bd..ba7f8d7516 100644 --- a/libraries/AP_HAL_Empty/PrivateMember.cpp +++ b/libraries/AP_HAL_Empty/PrivateMember.cpp @@ -3,9 +3,9 @@ using namespace Empty; -EmptyPrivateMember::EmptyPrivateMember(uint16_t foo) : +PrivateMember::PrivateMember(uint16_t foo) : _foo(foo) {} -void EmptyPrivateMember::init() {} +void PrivateMember::init() {} diff --git a/libraries/AP_HAL_Empty/PrivateMember.h b/libraries/AP_HAL_Empty/PrivateMember.h index 509c873352..f073f92355 100644 --- a/libraries/AP_HAL_Empty/PrivateMember.h +++ b/libraries/AP_HAL_Empty/PrivateMember.h @@ -7,9 +7,9 @@ #include "AP_HAL_Empty.h" -class Empty::EmptyPrivateMember { +class Empty::PrivateMember { public: - EmptyPrivateMember(uint16_t foo); + PrivateMember(uint16_t foo); void init(); private: uint16_t _foo; diff --git a/libraries/AP_HAL_Empty/RCInput.cpp b/libraries/AP_HAL_Empty/RCInput.cpp index f1935dc6df..086dedc0aa 100644 --- a/libraries/AP_HAL_Empty/RCInput.cpp +++ b/libraries/AP_HAL_Empty/RCInput.cpp @@ -2,26 +2,26 @@ #include "RCInput.h" using namespace Empty; -EmptyRCInput::EmptyRCInput() +RCInput::RCInput() {} -void EmptyRCInput::init() +void RCInput::init() {} -bool EmptyRCInput::new_input() { +bool RCInput::new_input() { return false; } -uint8_t EmptyRCInput::num_channels() { +uint8_t RCInput::num_channels() { return 0; } -uint16_t EmptyRCInput::read(uint8_t ch) { +uint16_t RCInput::read(uint8_t ch) { if (ch == 2) return 900; /* throttle should be low, for safety */ else return 1500; } -uint8_t EmptyRCInput::read(uint16_t* periods, uint8_t len) { +uint8_t RCInput::read(uint16_t* periods, uint8_t len) { for (uint8_t i = 0; i < len; i++){ if (i == 2) periods[i] = 900; else periods[i] = 1500; @@ -29,14 +29,14 @@ uint8_t EmptyRCInput::read(uint16_t* periods, uint8_t len) { return len; } -bool EmptyRCInput::set_overrides(int16_t *overrides, uint8_t len) { +bool RCInput::set_overrides(int16_t *overrides, uint8_t len) { return true; } -bool EmptyRCInput::set_override(uint8_t channel, int16_t override) { +bool RCInput::set_override(uint8_t channel, int16_t override) { return true; } -void EmptyRCInput::clear_overrides() +void RCInput::clear_overrides() {} diff --git a/libraries/AP_HAL_Empty/RCInput.h b/libraries/AP_HAL_Empty/RCInput.h index 14b3a1cb79..a24bba7677 100644 --- a/libraries/AP_HAL_Empty/RCInput.h +++ b/libraries/AP_HAL_Empty/RCInput.h @@ -4,9 +4,9 @@ #include "AP_HAL_Empty.h" -class Empty::EmptyRCInput : public AP_HAL::RCInput { +class Empty::RCInput : public AP_HAL::RCInput { public: - EmptyRCInput(); + RCInput(); void init(); bool new_input(); uint8_t num_channels(); diff --git a/libraries/AP_HAL_Empty/RCOutput.cpp b/libraries/AP_HAL_Empty/RCOutput.cpp index 55e74a5bd6..df144663c9 100644 --- a/libraries/AP_HAL_Empty/RCOutput.cpp +++ b/libraries/AP_HAL_Empty/RCOutput.cpp @@ -3,27 +3,27 @@ using namespace Empty; -void EmptyRCOutput::init() {} +void RCOutput::init() {} -void EmptyRCOutput::set_freq(uint32_t chmask, uint16_t freq_hz) {} +void RCOutput::set_freq(uint32_t chmask, uint16_t freq_hz) {} -uint16_t EmptyRCOutput::get_freq(uint8_t ch) { +uint16_t RCOutput::get_freq(uint8_t ch) { return 50; } -void EmptyRCOutput::enable_ch(uint8_t ch) +void RCOutput::enable_ch(uint8_t ch) {} -void EmptyRCOutput::disable_ch(uint8_t ch) +void RCOutput::disable_ch(uint8_t ch) {} -void EmptyRCOutput::write(uint8_t ch, uint16_t period_us) +void RCOutput::write(uint8_t ch, uint16_t period_us) {} -uint16_t EmptyRCOutput::read(uint8_t ch) { +uint16_t RCOutput::read(uint8_t ch) { return 900; } -void EmptyRCOutput::read(uint16_t* period_us, uint8_t len) +void RCOutput::read(uint16_t* period_us, uint8_t len) {} diff --git a/libraries/AP_HAL_Empty/RCOutput.h b/libraries/AP_HAL_Empty/RCOutput.h index 7290aa59fe..c831394672 100644 --- a/libraries/AP_HAL_Empty/RCOutput.h +++ b/libraries/AP_HAL_Empty/RCOutput.h @@ -4,7 +4,7 @@ #include "AP_HAL_Empty.h" -class Empty::EmptyRCOutput : public AP_HAL::RCOutput { +class Empty::RCOutput : public AP_HAL::RCOutput { void init(); void set_freq(uint32_t chmask, uint16_t freq_hz); uint16_t get_freq(uint8_t ch); diff --git a/libraries/AP_HAL_Empty/SPIDriver.cpp b/libraries/AP_HAL_Empty/SPIDriver.cpp index a6ca786e8c..a3e27bc55f 100644 --- a/libraries/AP_HAL_Empty/SPIDriver.cpp +++ b/libraries/AP_HAL_Empty/SPIDriver.cpp @@ -3,45 +3,45 @@ using namespace Empty; -EmptySPIDeviceDriver::EmptySPIDeviceDriver() +SPIDeviceDriver::SPIDeviceDriver() {} -void EmptySPIDeviceDriver::init() +void SPIDeviceDriver::init() {} -AP_HAL::Semaphore* EmptySPIDeviceDriver::get_semaphore() +AP_HAL::Semaphore* SPIDeviceDriver::get_semaphore() { return &_semaphore; } -bool EmptySPIDeviceDriver::transaction(const uint8_t *tx, uint8_t *rx, uint16_t len) +bool SPIDeviceDriver::transaction(const uint8_t *tx, uint8_t *rx, uint16_t len) { return true; } -void EmptySPIDeviceDriver::cs_assert() +void SPIDeviceDriver::cs_assert() {} -void EmptySPIDeviceDriver::cs_release() +void SPIDeviceDriver::cs_release() {} -uint8_t EmptySPIDeviceDriver::transfer (uint8_t data) +uint8_t SPIDeviceDriver::transfer (uint8_t data) { return 0; } -void EmptySPIDeviceDriver::transfer (const uint8_t *data, uint16_t len) +void SPIDeviceDriver::transfer (const uint8_t *data, uint16_t len) { } -EmptySPIDeviceManager::EmptySPIDeviceManager() +SPIDeviceManager::SPIDeviceManager() {} -void EmptySPIDeviceManager::init() +void SPIDeviceManager::init() {} -AP_HAL::SPIDeviceDriver* EmptySPIDeviceManager::device(enum AP_HAL::SPIDevice, uint8_t index) +AP_HAL::SPIDeviceDriver* SPIDeviceManager::device(enum AP_HAL::SPIDevice, uint8_t index) { return &_device; } diff --git a/libraries/AP_HAL_Empty/SPIDriver.h b/libraries/AP_HAL_Empty/SPIDriver.h index 4a3bd5d08e..3f651b1d61 100644 --- a/libraries/AP_HAL_Empty/SPIDriver.h +++ b/libraries/AP_HAL_Empty/SPIDriver.h @@ -5,9 +5,9 @@ #include "AP_HAL_Empty.h" #include "Semaphores.h" -class Empty::EmptySPIDeviceDriver : public AP_HAL::SPIDeviceDriver { +class Empty::SPIDeviceDriver : public AP_HAL::SPIDeviceDriver { public: - EmptySPIDeviceDriver(); + SPIDeviceDriver(); void init(); AP_HAL::Semaphore* get_semaphore(); bool transaction(const uint8_t *tx, uint8_t *rx, uint16_t len); @@ -17,16 +17,16 @@ public: uint8_t transfer (uint8_t data); void transfer (const uint8_t *data, uint16_t len); private: - EmptySemaphore _semaphore; + Semaphore _semaphore; }; -class Empty::EmptySPIDeviceManager : public AP_HAL::SPIDeviceManager { +class Empty::SPIDeviceManager : public AP_HAL::SPIDeviceManager { public: - EmptySPIDeviceManager(); + SPIDeviceManager(); void init(); AP_HAL::SPIDeviceDriver* device(enum AP_HAL::SPIDevice, uint8_t index); private: - EmptySPIDeviceDriver _device; + SPIDeviceDriver _device; }; #endif // __AP_HAL_EMPTY_SPIDRIVER_H__ diff --git a/libraries/AP_HAL_Empty/Scheduler.cpp b/libraries/AP_HAL_Empty/Scheduler.cpp index 39cd9a1ff8..fa63ec2f5d 100644 --- a/libraries/AP_HAL_Empty/Scheduler.cpp +++ b/libraries/AP_HAL_Empty/Scheduler.cpp @@ -7,54 +7,54 @@ using namespace Empty; extern const AP_HAL::HAL& hal; -EmptyScheduler::EmptyScheduler() +Scheduler::Scheduler() {} -void EmptyScheduler::init() +void Scheduler::init() {} -void EmptyScheduler::delay(uint16_t ms) +void Scheduler::delay(uint16_t ms) {} -void EmptyScheduler::delay_microseconds(uint16_t us) +void Scheduler::delay_microseconds(uint16_t us) {} -void EmptyScheduler::register_delay_callback(AP_HAL::Proc k, +void Scheduler::register_delay_callback(AP_HAL::Proc k, uint16_t min_time_ms) {} -void EmptyScheduler::register_timer_process(AP_HAL::MemberProc k) +void Scheduler::register_timer_process(AP_HAL::MemberProc k) {} -void EmptyScheduler::register_io_process(AP_HAL::MemberProc k) +void Scheduler::register_io_process(AP_HAL::MemberProc k) {} -void EmptyScheduler::register_timer_failsafe(AP_HAL::Proc, uint32_t period_us) +void Scheduler::register_timer_failsafe(AP_HAL::Proc, uint32_t period_us) {} -void EmptyScheduler::suspend_timer_procs() +void Scheduler::suspend_timer_procs() {} -void EmptyScheduler::resume_timer_procs() +void Scheduler::resume_timer_procs() {} -bool EmptyScheduler::in_timerprocess() { +bool Scheduler::in_timerprocess() { return false; } -void EmptyScheduler::begin_atomic() +void Scheduler::begin_atomic() {} -void EmptyScheduler::end_atomic() +void Scheduler::end_atomic() {} -bool EmptyScheduler::system_initializing() { +bool Scheduler::system_initializing() { return false; } -void EmptyScheduler::system_initialized() +void Scheduler::system_initialized() {} -void EmptyScheduler::reboot(bool hold_in_bootloader) { +void Scheduler::reboot(bool hold_in_bootloader) { for(;;); } diff --git a/libraries/AP_HAL_Empty/Scheduler.h b/libraries/AP_HAL_Empty/Scheduler.h index bef1e43c84..61b025a873 100644 --- a/libraries/AP_HAL_Empty/Scheduler.h +++ b/libraries/AP_HAL_Empty/Scheduler.h @@ -4,9 +4,9 @@ #include "AP_HAL_Empty.h" -class Empty::EmptyScheduler : public AP_HAL::Scheduler { +class Empty::Scheduler : public AP_HAL::Scheduler { public: - EmptyScheduler(); + Scheduler(); void init(); void delay(uint16_t ms); void delay_microseconds(uint16_t us); diff --git a/libraries/AP_HAL_Empty/Semaphores.cpp b/libraries/AP_HAL_Empty/Semaphores.cpp index c4f45e2559..f8680c42bd 100644 --- a/libraries/AP_HAL_Empty/Semaphores.cpp +++ b/libraries/AP_HAL_Empty/Semaphores.cpp @@ -3,7 +3,7 @@ using namespace Empty; -bool EmptySemaphore::give() { +bool Semaphore::give() { if (_taken) { _taken = false; return true; @@ -12,11 +12,11 @@ bool EmptySemaphore::give() { } } -bool EmptySemaphore::take(uint32_t timeout_ms) { +bool Semaphore::take(uint32_t timeout_ms) { return take_nonblocking(); } -bool EmptySemaphore::take_nonblocking() { +bool Semaphore::take_nonblocking() { /* No syncronisation primitives to garuntee this is correct */ if (!_taken) { _taken = true; diff --git a/libraries/AP_HAL_Empty/Semaphores.h b/libraries/AP_HAL_Empty/Semaphores.h index 46848b1d3a..38279db9be 100644 --- a/libraries/AP_HAL_Empty/Semaphores.h +++ b/libraries/AP_HAL_Empty/Semaphores.h @@ -4,9 +4,9 @@ #include "AP_HAL_Empty.h" -class Empty::EmptySemaphore : public AP_HAL::Semaphore { +class Empty::Semaphore : public AP_HAL::Semaphore { public: - EmptySemaphore() : _taken(false) {} + Semaphore() : _taken(false) {} bool give(); bool take(uint32_t timeout_ms); bool take_nonblocking(); diff --git a/libraries/AP_HAL_Empty/Storage.cpp b/libraries/AP_HAL_Empty/Storage.cpp index fc87a658df..0bb12aa9f6 100644 --- a/libraries/AP_HAL_Empty/Storage.cpp +++ b/libraries/AP_HAL_Empty/Storage.cpp @@ -4,16 +4,16 @@ using namespace Empty; -EmptyStorage::EmptyStorage() +Storage::Storage() {} -void EmptyStorage::init() +void Storage::init() {} -void EmptyStorage::read_block(void* dst, uint16_t src, size_t n) { +void Storage::read_block(void* dst, uint16_t src, size_t n) { memset(dst, 0, n); } -void EmptyStorage::write_block(uint16_t loc, const void* src, size_t n) +void Storage::write_block(uint16_t loc, const void* src, size_t n) {} diff --git a/libraries/AP_HAL_Empty/Storage.h b/libraries/AP_HAL_Empty/Storage.h index 1dacb452f7..3eb66063d3 100644 --- a/libraries/AP_HAL_Empty/Storage.h +++ b/libraries/AP_HAL_Empty/Storage.h @@ -4,9 +4,9 @@ #include "AP_HAL_Empty.h" -class Empty::EmptyStorage : public AP_HAL::Storage { +class Empty::Storage : public AP_HAL::Storage { public: - EmptyStorage(); + Storage(); void init(); void read_block(void *dst, uint16_t src, size_t n); void write_block(uint16_t dst, const void* src, size_t n); diff --git a/libraries/AP_HAL_Empty/UARTDriver.cpp b/libraries/AP_HAL_Empty/UARTDriver.cpp index 8969837375..7689a2386e 100644 --- a/libraries/AP_HAL_Empty/UARTDriver.cpp +++ b/libraries/AP_HAL_Empty/UARTDriver.cpp @@ -3,25 +3,25 @@ using namespace Empty; -EmptyUARTDriver::EmptyUARTDriver() {} +UARTDriver::UARTDriver() {} -void EmptyUARTDriver::begin(uint32_t b) {} -void EmptyUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS) {} -void EmptyUARTDriver::end() {} -void EmptyUARTDriver::flush() {} -bool EmptyUARTDriver::is_initialized() { return false; } -void EmptyUARTDriver::set_blocking_writes(bool blocking) {} -bool EmptyUARTDriver::tx_pending() { return false; } +void UARTDriver::begin(uint32_t b) {} +void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS) {} +void UARTDriver::end() {} +void UARTDriver::flush() {} +bool UARTDriver::is_initialized() { return false; } +void UARTDriver::set_blocking_writes(bool blocking) {} +bool UARTDriver::tx_pending() { return false; } /* Empty implementations of Stream virtual methods */ -int16_t EmptyUARTDriver::available() { return 0; } -int16_t EmptyUARTDriver::txspace() { return 1; } -int16_t EmptyUARTDriver::read() { return -1; } +int16_t UARTDriver::available() { return 0; } +int16_t UARTDriver::txspace() { return 1; } +int16_t UARTDriver::read() { return -1; } /* Empty implementations of Print virtual methods */ -size_t EmptyUARTDriver::write(uint8_t c) { return 0; } +size_t UARTDriver::write(uint8_t c) { return 0; } -size_t EmptyUARTDriver::write(const uint8_t *buffer, size_t size) +size_t UARTDriver::write(const uint8_t *buffer, size_t size) { size_t n = 0; while (size--) { diff --git a/libraries/AP_HAL_Empty/UARTDriver.h b/libraries/AP_HAL_Empty/UARTDriver.h index a66b690bbb..11cadf5d45 100644 --- a/libraries/AP_HAL_Empty/UARTDriver.h +++ b/libraries/AP_HAL_Empty/UARTDriver.h @@ -4,9 +4,9 @@ #include "AP_HAL_Empty.h" -class Empty::EmptyUARTDriver : public AP_HAL::UARTDriver { +class Empty::UARTDriver : public AP_HAL::UARTDriver { public: - EmptyUARTDriver(); + UARTDriver(); /* Empty implementations of UARTDriver virtual methods */ void begin(uint32_t b); void begin(uint32_t b, uint16_t rxS, uint16_t txS); diff --git a/libraries/AP_HAL_Empty/Util.h b/libraries/AP_HAL_Empty/Util.h index 44bae3e34f..369af241bb 100644 --- a/libraries/AP_HAL_Empty/Util.h +++ b/libraries/AP_HAL_Empty/Util.h @@ -5,7 +5,7 @@ #include #include "AP_HAL_Empty_Namespace.h" -class Empty::EmptyUtil : public AP_HAL::Util { +class Empty::Util : public AP_HAL::Util { public: bool run_debug_shell(AP_HAL::BetterStream *stream) { return false; } };