AP_HAL_VRBRAIN: 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 4c82c535cc
commit bf24d0ef31
10 changed files with 13 additions and 13 deletions

View File

@ -190,7 +190,7 @@ VRBRAINAnalogIn::VRBRAINAnalogIn() :
_power_flags(0)
{}
void VRBRAINAnalogIn::init(void* machtnichts)
void VRBRAINAnalogIn::init()
{
_adc_fd = open(ADC_DEVICE_PATH, O_RDONLY | O_NONBLOCK);
if (_adc_fd == -1) {

View File

@ -56,7 +56,7 @@ private:
class VRBRAIN::VRBRAINAnalogIn : public AP_HAL::AnalogIn {
public:
VRBRAINAnalogIn();
void init(void* implspecific);
void init();
AP_HAL::AnalogSource* channel(int16_t pin);
void _timer_tick(void);
float board_voltage(void) { return _board_voltage; }

View File

@ -159,10 +159,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();

View File

@ -9,7 +9,7 @@ using namespace VRBRAIN;
extern const AP_HAL::HAL& hal;
void VRBRAINRCInput::init(void* unused)
void VRBRAINRCInput::init()
{
_perf_rcin = perf_alloc(PC_ELAPSED, "APM_rcin");
_rc_sub = orb_subscribe(ORB_ID(input_rc));

View File

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

View File

@ -16,7 +16,7 @@ extern const AP_HAL::HAL& hal;
using namespace VRBRAIN;
void VRBRAINRCOutput::init(void* unused)
void VRBRAINRCOutput::init()
{
_perf_rcout = perf_alloc(PC_ELAPSED, "APM_rcout");
_pwm_fd = open(PWM_OUTPUT_DEVICE_PATH, O_RDWR);

View File

@ -10,7 +10,7 @@
class VRBRAIN::VRBRAINRCOutput : 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);

View File

@ -36,7 +36,7 @@ VRBRAINScheduler::VRBRAINScheduler() :
_perf_delay(perf_alloc(PC_ELAPSED, "APM_delay"))
{}
void VRBRAINScheduler::init(void *unused)
void VRBRAINScheduler::init()
{
_main_task_pid = getpid();

View File

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

View File

@ -17,7 +17,7 @@ class VRBRAIN::VRBRAINStorage : public AP_HAL::Storage {
public:
VRBRAINStorage();
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);