AP_HAL_SITL: 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 0c3733601b
commit 4c82c535cc
10 changed files with 14 additions and 14 deletions

View File

@ -55,7 +55,7 @@ void ADCSource::set_pin(uint8_t pin) {
_pin = pin; _pin = pin;
} }
void SITLAnalogIn::init(void *ap_hal_scheduler) { void SITLAnalogIn::init() {
} }
AP_HAL::AnalogSource* SITLAnalogIn::channel(int16_t pin) { AP_HAL::AnalogSource* SITLAnalogIn::channel(int16_t pin) {

View File

@ -37,7 +37,7 @@ public:
SITLAnalogIn(SITL_State *sitlState) { SITLAnalogIn(SITL_State *sitlState) {
_sitlState = sitlState; _sitlState = sitlState;
} }
void init(void* ap_hal_scheduler); void init();
AP_HAL::AnalogSource* channel(int16_t n); AP_HAL::AnalogSource* channel(int16_t n);
float board_voltage(void) { float board_voltage(void) {
return 5.0f; return 5.0f;

View File

@ -71,16 +71,16 @@ void HAL_SITL::run(int argc, char * const argv[], Callbacks* callbacks) const
assert(callbacks); assert(callbacks);
_sitl_state->init(argc, argv); _sitl_state->init(argc, argv);
scheduler->init(NULL); scheduler->init();
uartA->begin(115200); uartA->begin(115200);
rcin->init(NULL); rcin->init();
rcout->init(NULL); rcout->init();
//spi->init(NULL); //spi->init();
//i2c->begin(); //i2c->begin();
//i2c->setTimeout(100); //i2c->setTimeout(100);
analogin->init(NULL); analogin->init();
callbacks->setup(); callbacks->setup();
scheduler->system_initialized(); scheduler->system_initialized();

View File

@ -7,7 +7,7 @@ using namespace HALSITL;
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;
void SITLRCInput::init(void* machtnichts) void SITLRCInput::init()
{ {
clear_overrides(); clear_overrides();
} }

View File

@ -11,7 +11,7 @@ public:
SITLRCInput(SITL_State *sitlState) { SITLRCInput(SITL_State *sitlState) {
_sitlState = sitlState; _sitlState = sitlState;
} }
void init(void* machtnichts); void init();
bool new_input(); bool new_input();
uint8_t num_channels() { uint8_t num_channels() {
return 8; return 8;

View File

@ -5,7 +5,7 @@
using namespace HALSITL; using namespace HALSITL;
void SITLRCOutput::init(void* machtnichts) {} void SITLRCOutput::init() {}
void SITLRCOutput::set_freq(uint32_t chmask, uint16_t freq_hz) { void SITLRCOutput::set_freq(uint32_t chmask, uint16_t freq_hz) {
_freq_hz = freq_hz; _freq_hz = freq_hz;

View File

@ -12,7 +12,7 @@ public:
_sitlState = sitlState; _sitlState = sitlState;
_freq_hz = 50; _freq_hz = 50;
} }
void init(void* machtnichts); void init();
void set_freq(uint32_t chmask, uint16_t freq_hz); void set_freq(uint32_t chmask, uint16_t freq_hz);
uint16_t get_freq(uint8_t ch); uint16_t get_freq(uint8_t ch);
void enable_ch(uint8_t ch); void enable_ch(uint8_t ch);

View File

@ -33,7 +33,7 @@ SITLScheduler::SITLScheduler(SITL_State *sitlState) :
{ {
} }
void SITLScheduler::init(void *unused) void SITLScheduler::init()
{ {
} }

View File

@ -19,7 +19,7 @@ public:
/* AP_HAL::Scheduler methods */ /* AP_HAL::Scheduler methods */
void init(void *unused); void init();
void delay(uint16_t ms); void delay(uint16_t ms);
void delay_microseconds(uint16_t us); void delay_microseconds(uint16_t us);
void register_delay_callback(AP_HAL::Proc, uint16_t min_time_ms); void register_delay_callback(AP_HAL::Proc, uint16_t min_time_ms);

View File

@ -11,7 +11,7 @@ public:
SITLEEPROMStorage() { SITLEEPROMStorage() {
_eeprom_fd = -1; _eeprom_fd = -1;
} }
void init(void* machtnichts) {} void init() {}
void read_block(void *dst, uint16_t src, size_t n); void read_block(void *dst, uint16_t src, size_t n);
void write_block(uint16_t dst, const void* src, size_t n); void write_block(uint16_t dst, const void* src, size_t n);