diff --git a/libraries/AP_HAL_PX4/AnalogIn.cpp b/libraries/AP_HAL_PX4/AnalogIn.cpp index 5f2789979a..340f7f95fb 100644 --- a/libraries/AP_HAL_PX4/AnalogIn.cpp +++ b/libraries/AP_HAL_PX4/AnalogIn.cpp @@ -198,7 +198,7 @@ PX4AnalogIn::PX4AnalogIn() : _power_flags(0) {} -void PX4AnalogIn::init(void* machtnichts) +void PX4AnalogIn::init() { _adc_fd = open(ADC0_DEVICE_PATH, O_RDONLY | O_NONBLOCK); if (_adc_fd == -1) { diff --git a/libraries/AP_HAL_PX4/AnalogIn.h b/libraries/AP_HAL_PX4/AnalogIn.h index f452364e0c..657c2707c8 100644 --- a/libraries/AP_HAL_PX4/AnalogIn.h +++ b/libraries/AP_HAL_PX4/AnalogIn.h @@ -55,7 +55,7 @@ private: class PX4::PX4AnalogIn : public AP_HAL::AnalogIn { public: PX4AnalogIn(); - void init(void* implspecific); + void init(); AP_HAL::AnalogSource* channel(int16_t pin); void _timer_tick(void); float board_voltage(void) { return _board_voltage; } diff --git a/libraries/AP_HAL_PX4/HAL_PX4_Class.cpp b/libraries/AP_HAL_PX4/HAL_PX4_Class.cpp index c928eaffda..da2a4a9d42 100644 --- a/libraries/AP_HAL_PX4/HAL_PX4_Class.cpp +++ b/libraries/AP_HAL_PX4/HAL_PX4_Class.cpp @@ -123,10 +123,10 @@ static int main_loop(int argc, char **argv) hal.uartC->begin(57600); hal.uartD->begin(57600); hal.uartE->begin(57600); - hal.scheduler->init(NULL); - hal.rcin->init(NULL); - hal.rcout->init(NULL); - hal.analogin->init(NULL); + hal.scheduler->init(); + hal.rcin->init(); + hal.rcout->init(); + hal.analogin->init(); hal.gpio->init(); diff --git a/libraries/AP_HAL_PX4/RCInput.cpp b/libraries/AP_HAL_PX4/RCInput.cpp index 9212a6c187..d1e3078262 100644 --- a/libraries/AP_HAL_PX4/RCInput.cpp +++ b/libraries/AP_HAL_PX4/RCInput.cpp @@ -12,7 +12,7 @@ using namespace PX4; extern const AP_HAL::HAL& hal; -void PX4RCInput::init(void* unused) +void PX4RCInput::init() { _perf_rcin = perf_alloc(PC_ELAPSED, "APM_rcin"); _rc_sub = orb_subscribe(ORB_ID(input_rc)); diff --git a/libraries/AP_HAL_PX4/RCInput.h b/libraries/AP_HAL_PX4/RCInput.h index ebfeac073c..7cdd0301a8 100644 --- a/libraries/AP_HAL_PX4/RCInput.h +++ b/libraries/AP_HAL_PX4/RCInput.h @@ -14,7 +14,7 @@ class PX4::PX4RCInput : public AP_HAL::RCInput { public: - void init(void* machtnichts); + void init(); bool new_input(); uint8_t num_channels(); uint16_t read(uint8_t ch); diff --git a/libraries/AP_HAL_PX4/RCOutput.cpp b/libraries/AP_HAL_PX4/RCOutput.cpp index 9a5be9b6e6..590ec4179a 100644 --- a/libraries/AP_HAL_PX4/RCOutput.cpp +++ b/libraries/AP_HAL_PX4/RCOutput.cpp @@ -18,7 +18,7 @@ extern const AP_HAL::HAL& hal; using namespace PX4; -void PX4RCOutput::init(void* unused) +void PX4RCOutput::init() { _perf_rcout = perf_alloc(PC_ELAPSED, "APM_rcout"); _pwm_fd = open(PWM_OUTPUT0_DEVICE_PATH, O_RDWR); diff --git a/libraries/AP_HAL_PX4/RCOutput.h b/libraries/AP_HAL_PX4/RCOutput.h index 38d7f51deb..2ec97d97f8 100644 --- a/libraries/AP_HAL_PX4/RCOutput.h +++ b/libraries/AP_HAL_PX4/RCOutput.h @@ -12,7 +12,7 @@ class PX4::PX4RCOutput : public AP_HAL::RCOutput { public: - 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); diff --git a/libraries/AP_HAL_PX4/Scheduler.cpp b/libraries/AP_HAL_PX4/Scheduler.cpp index d02bcd5edd..2aee553253 100644 --- a/libraries/AP_HAL_PX4/Scheduler.cpp +++ b/libraries/AP_HAL_PX4/Scheduler.cpp @@ -37,7 +37,7 @@ PX4Scheduler::PX4Scheduler() : _perf_delay(perf_alloc(PC_ELAPSED, "APM_delay")) {} -void PX4Scheduler::init(void *unused) +void PX4Scheduler::init() { _main_task_pid = getpid(); diff --git a/libraries/AP_HAL_PX4/Scheduler.h b/libraries/AP_HAL_PX4/Scheduler.h index 61ffa60e4c..b39a74b391 100644 --- a/libraries/AP_HAL_PX4/Scheduler.h +++ b/libraries/AP_HAL_PX4/Scheduler.h @@ -45,7 +45,7 @@ public: PX4Scheduler(); /* AP_HAL::Scheduler methods */ - void init(void *unused); + void init(); void delay(uint16_t ms); void delay_microseconds(uint16_t us); void delay_microseconds_boost(uint16_t us); diff --git a/libraries/AP_HAL_PX4/Storage.h b/libraries/AP_HAL_PX4/Storage.h index 35051e8d49..dc3da51226 100644 --- a/libraries/AP_HAL_PX4/Storage.h +++ b/libraries/AP_HAL_PX4/Storage.h @@ -17,7 +17,7 @@ class PX4::PX4Storage : public AP_HAL::Storage { public: PX4Storage(); - void init(void* machtnichts) {} + 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);