AP_HAL_Empty: use init() method without arguments

Override the init() method from parent class that doesn't have a
parameter since it's not used here.
This commit is contained in:
Lucas De Marchi 2015-12-02 13:14:20 -02:00
parent 6bc07da0ee
commit 00f17466a8
13 changed files with 13 additions and 13 deletions

View File

@ -34,7 +34,7 @@ void EmptyAnalogSource::set_settle_time(uint16_t settle_time_ms)
EmptyAnalogIn::EmptyAnalogIn()
{}
void EmptyAnalogIn::init(void* machtnichts)
void EmptyAnalogIn::init()
{}
AP_HAL::AnalogSource* EmptyAnalogIn::channel(int16_t n) {

View File

@ -22,7 +22,7 @@ private:
class Empty::EmptyAnalogIn : public AP_HAL::AnalogIn {
public:
EmptyAnalogIn();
void init(void* implspecific);
void init();
AP_HAL::AnalogSource* channel(int16_t n);
float board_voltage(void);
};

View File

@ -52,7 +52,7 @@ void HAL_Empty::run(int argc, char* const argv[], Callbacks* callbacks) const
/* initialize all drivers and private members here.
* up to the programmer to do this in the correct order.
* Scheduler should likely come first. */
scheduler->init(NULL);
scheduler->init();
uartA->begin(115200);
_member->init();

View File

@ -5,7 +5,7 @@ using namespace Empty;
EmptyRCInput::EmptyRCInput()
{}
void EmptyRCInput::init(void* machtnichts)
void EmptyRCInput::init()
{}
bool EmptyRCInput::new_input() {

View File

@ -7,7 +7,7 @@
class Empty::EmptyRCInput : public AP_HAL::RCInput {
public:
EmptyRCInput();
void init(void* machtnichts);
void init();
bool new_input();
uint8_t num_channels();
uint16_t read(uint8_t ch);

View File

@ -3,7 +3,7 @@
using namespace Empty;
void EmptyRCOutput::init(void* machtnichts) {}
void EmptyRCOutput::init() {}
void EmptyRCOutput::set_freq(uint32_t chmask, uint16_t freq_hz) {}

View File

@ -5,7 +5,7 @@
#include "AP_HAL_Empty.h"
class Empty::EmptyRCOutput : public AP_HAL::RCOutput {
void init(void* machtnichts);
void init();
void set_freq(uint32_t chmask, uint16_t freq_hz);
uint16_t get_freq(uint8_t ch);
void enable_ch(uint8_t ch);

View File

@ -38,7 +38,7 @@ void EmptySPIDeviceDriver::transfer (const uint8_t *data, uint16_t len)
EmptySPIDeviceManager::EmptySPIDeviceManager()
{}
void EmptySPIDeviceManager::init(void *)
void EmptySPIDeviceManager::init()
{}
AP_HAL::SPIDeviceDriver* EmptySPIDeviceManager::device(enum AP_HAL::SPIDevice, uint8_t index)

View File

@ -23,7 +23,7 @@ private:
class Empty::EmptySPIDeviceManager : public AP_HAL::SPIDeviceManager {
public:
EmptySPIDeviceManager();
void init(void *);
void init();
AP_HAL::SPIDeviceDriver* device(enum AP_HAL::SPIDevice, uint8_t index);
private:
EmptySPIDeviceDriver _device;

View File

@ -10,7 +10,7 @@ extern const AP_HAL::HAL& hal;
EmptyScheduler::EmptyScheduler()
{}
void EmptyScheduler::init(void* machtnichts)
void EmptyScheduler::init()
{}
void EmptyScheduler::delay(uint16_t ms)

View File

@ -7,7 +7,7 @@
class Empty::EmptyScheduler : public AP_HAL::Scheduler {
public:
EmptyScheduler();
void init(void* machtnichts);
void init();
void delay(uint16_t ms);
void delay_microseconds(uint16_t us);
void register_delay_callback(AP_HAL::Proc,

View File

@ -7,7 +7,7 @@ using namespace Empty;
EmptyStorage::EmptyStorage()
{}
void EmptyStorage::init(void*)
void EmptyStorage::init()
{}
void EmptyStorage::read_block(void* dst, uint16_t src, size_t n) {

View File

@ -7,7 +7,7 @@
class Empty::EmptyStorage : public AP_HAL::Storage {
public:
EmptyStorage();
void init(void *);
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);
};