AP_HAL_Linux: 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 0514aadaec
commit 2439826c19
42 changed files with 46 additions and 46 deletions

View File

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

View File

@ -22,7 +22,7 @@ private:
class Linux::AnalogIn : public AP_HAL::AnalogIn {
public:
AnalogIn();
void init(void* implspecific);
void init();
AP_HAL::AnalogSource* channel(int16_t n);
// we don't yet know how to get the board voltage

View File

@ -74,7 +74,7 @@ AP_HAL::AnalogSource* ADS1115AnalogIn::channel(int16_t pin)
return NULL;
}
void ADS1115AnalogIn::init(void* implspecific)
void ADS1115AnalogIn::init()
{
_adc->init();
hal.scheduler->suspend_timer_procs();

View File

@ -26,7 +26,7 @@ private:
class ADS1115AnalogIn: public AP_HAL::AnalogIn {
public:
ADS1115AnalogIn();
void init(void* implspecific);
void init();
AP_HAL::AnalogSource* channel(int16_t n);
/* Board voltage is not available */

View File

@ -246,7 +246,7 @@ void HAL_Linux::run(int argc, char* const argv[], Callbacks* callbacks) const
}
}
scheduler->init(NULL);
scheduler->init();
gpio->init();
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
i2c->begin();
@ -258,12 +258,12 @@ void HAL_Linux::run(int argc, char* const argv[], Callbacks* callbacks) const
#else
i2c->begin();
#endif
spi->init(NULL);
rcout->init(NULL);
rcin->init(NULL);
spi->init();
rcout->init();
rcin->init();
uartA->begin(115200);
uartE->begin(115200);
analogin->init(NULL);
analogin->init();
utilInstance.init(argc+gopt.optind-1, &argv[gopt.optind-1]);
// NOTE: See commit 9f5b4ffca ("AP_HAL_Linux_Class: Correct

View File

@ -28,7 +28,7 @@ RCInput::RCInput() :
ppm_state._channel_counter = -1;
}
void RCInput::init(void* machtnichts)
void RCInput::init()
{
}

View File

@ -14,7 +14,7 @@ public:
return static_cast<RCInput*>(rcinput);
}
virtual void init(void* machtnichts);
virtual void init();
bool new_input();
uint8_t num_channels();
uint16_t read(uint8_t ch);

View File

@ -34,7 +34,7 @@ extern const AP_HAL::HAL& hal;
using namespace Linux;
void RCInput_AioPRU::init(void*)
void RCInput_AioPRU::init()
{
int mem_fd = open("/dev/mem", O_RDWR|O_SYNC);
if (mem_fd == -1) {

View File

@ -27,7 +27,7 @@
class Linux::RCInput_AioPRU : public Linux::RCInput
{
public:
void init(void*);
void init();
void _timer_tick(void);
private:

View File

@ -24,7 +24,7 @@ extern const AP_HAL::HAL& hal;
using namespace Linux;
void RCInput_PRU::init(void*)
void RCInput_PRU::init()
{
int mem_fd = open("/dev/mem", O_RDWR|O_SYNC);
if (mem_fd == -1) {

View File

@ -16,7 +16,7 @@
class Linux::RCInput_PRU : public Linux::RCInput
{
public:
void init(void*);
void init();
void _timer_tick(void);
private:

View File

@ -423,7 +423,7 @@ void RCInput_RPI::init_registers()
clk_reg = (uint32_t*)map_peripheral(clk_base, RCIN_RPI_CLK_LEN);
}
void RCInput_RPI::init(void*)
void RCInput_RPI::init()
{
init_registers();

View File

@ -77,7 +77,7 @@ public:
class Linux::RCInput_RPI : public Linux::RCInput
{
public:
void init(void*);
void init();
void _timer_tick(void);
RCInput_RPI();
~RCInput_RPI();

View File

@ -19,7 +19,7 @@ static const AP_HAL::HAL& hal = AP_HAL::get_HAL();
using namespace Linux;
void RCInput_Raspilot::init(void*)
void RCInput_Raspilot::init()
{
_spi = hal.spi->device(AP_HAL::SPIDevice_RASPIO);
_spi_sem = _spi->get_semaphore();

View File

@ -8,7 +8,7 @@
class Linux::RCInput_Raspilot : public Linux::RCInput
{
public:
void init(void*);
void init();
private:
uint32_t _last_timer;

View File

@ -31,7 +31,7 @@ RCInput_UART::~RCInput_UART()
close(_fd);
}
void RCInput_UART::init(void*)
void RCInput_UART::init()
{
struct termios options;

View File

@ -13,7 +13,7 @@ public:
RCInput_UART(const char *path);
~RCInput_UART();
void init(void*) override;
void init() override;
void _timer_tick(void) override;
private:

View File

@ -14,7 +14,7 @@ RCInput_UDP::RCInput_UDP() :
_last_buf_seq(0)
{}
void RCInput_UDP::init(void *)
void RCInput_UDP::init()
{
_port = RCINPUT_UDP_DEF_PORT;
if(!_socket.bind("0.0.0.0", _port)) {

View File

@ -12,7 +12,7 @@ class Linux::RCInput_UDP : public Linux::RCInput
{
public:
RCInput_UDP();
void init(void*);
void init();
void _timer_tick(void);
private:
SocketAPM _socket{true};

View File

@ -21,7 +21,7 @@ extern const AP_HAL::HAL& hal;
using namespace Linux;
void RCInput_ZYNQ::init(void*)
void RCInput_ZYNQ::init()
{
int mem_fd = open("/dev/mem", O_RDWR|O_SYNC);
if (mem_fd == -1) {

View File

@ -15,7 +15,7 @@
class Linux::RCInput_ZYNQ : public Linux::RCInput
{
public:
void init(void*);
void init();
void _timer_tick(void);
private:

View File

@ -31,7 +31,7 @@ static void catch_sigbus(int sig)
{
AP_HAL::panic("RCOutputAioPRU.cpp:SIGBUS error gernerated\n");
}
void RCOutput_AioPRU::init(void* machtnicht)
void RCOutput_AioPRU::init()
{
uint32_t mem_fd;
uint32_t *iram;

View File

@ -20,7 +20,7 @@
#define PWM_CHAN_COUNT 12
class Linux::RCOutput_AioPRU : 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

@ -238,7 +238,7 @@ uint16_t RCOutput_Bebop::_period_us_to_rpm(uint16_t period_us)
return (uint16_t)rpm_fl;
}
void RCOutput_Bebop::init(void* dummy)
void RCOutput_Bebop::init()
{
int ret=0;
struct sched_param param = { .sched_priority = RCOUT_BEBOP_RTPRIO };

View File

@ -55,7 +55,7 @@ public:
return static_cast<RCOutput_Bebop*>(rcout);
}
void init(void* dummy);
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

@ -80,7 +80,7 @@ RCOutput_PCA9685::~RCOutput_PCA9685()
delete [] _pulses_buffer;
}
void RCOutput_PCA9685::init(void* machtnicht)
void RCOutput_PCA9685::init()
{
_i2c_sem = hal.i2c->get_semaphore();
if (_i2c_sem == NULL) {

View File

@ -13,7 +13,7 @@ class Linux::RCOutput_PCA9685 : public AP_HAL::RCOutput {
RCOutput_PCA9685(uint8_t addr, bool external_clock, uint8_t channel_offset,
int16_t oe_pin_number);
~RCOutput_PCA9685();
void init(void* machtnichts);
void init();
void reset_all_channels();
void set_freq(uint32_t chmask, uint16_t freq_hz);
uint16_t get_freq(uint8_t ch);

View File

@ -28,7 +28,7 @@ static void catch_sigbus(int sig)
{
AP_HAL::panic("RCOutput.cpp:SIGBUS error gernerated\n");
}
void RCOutput_PRU::init(void* machtnicht)
void RCOutput_PRU::init()
{
uint32_t mem_fd;
signal(SIGBUS,catch_sigbus);

View File

@ -16,7 +16,7 @@
#define PWM_CMD_TEST 6 /* various crap */
class Linux::RCOutput_PRU : 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

@ -22,7 +22,7 @@ using namespace Linux;
static const AP_HAL::HAL& hal = AP_HAL::get_HAL();
void RCOutput_Raspilot::init(void* machtnicht)
void RCOutput_Raspilot::init()
{
_spi = hal.spi->device(AP_HAL::SPIDevice_RASPIO);
_spi_sem = _spi->get_semaphore();

View File

@ -5,7 +5,7 @@
#include "AP_HAL_Linux.h"
class Linux::RCOutput_Raspilot : 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

@ -43,7 +43,7 @@ RCOutput_Sysfs::~RCOutput_Sysfs()
delete _pwm_channels;
}
void RCOutput_Sysfs::init(void *machtnichts)
void RCOutput_Sysfs::init()
{
for (uint8_t i = 0; i < _channel_count; i++) {
_pwm_channels[i] = new PWM_Sysfs(_chip, i);

View File

@ -13,7 +13,7 @@ public:
return static_cast<RCOutput_Sysfs *>(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

@ -24,7 +24,7 @@ static void catch_sigbus(int sig)
{
AP_HAL::panic("RCOutput.cpp:SIGBUS error gernerated\n");
}
void RCOutput_ZYNQ::init(void* machtnicht)
void RCOutput_ZYNQ::init()
{
uint32_t mem_fd;
signal(SIGBUS,catch_sigbus);

View File

@ -15,7 +15,7 @@
class Linux::RCOutput_ZYNQ : 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

@ -83,7 +83,7 @@ AP_HAL::AnalogSource* RaspilotAnalogIn::channel(int16_t pin)
return NULL;
}
void RaspilotAnalogIn::init(void* implspecific)
void RaspilotAnalogIn::init()
{
_vcc_pin_analog_source = channel(4);

View File

@ -26,7 +26,7 @@ private:
class RaspilotAnalogIn: public AP_HAL::AnalogIn {
public:
RaspilotAnalogIn();
void init(void* implspecific);
void init();
AP_HAL::AnalogSource* channel(int16_t n);
/* Board voltage is not available */

View File

@ -146,7 +146,7 @@ void SPIDeviceDriver::transfer(const uint8_t *data, uint16_t len)
transaction(data, NULL, len);
}
void SPIDeviceManager::init(void *)
void SPIDeviceManager::init()
{
for (uint8_t i=0; i<LINUX_SPI_DEVICE_NUM_DEVICES; i++) {
if (_device[i]._bus >= LINUX_SPI_MAX_BUSES) {

View File

@ -48,7 +48,7 @@ private:
class Linux::SPIDeviceManager : public AP_HAL::SPIDeviceManager {
public:
void init(void *);
void init();
AP_HAL::SPIDeviceDriver* device(enum AP_HAL::SPIDevice, uint8_t index = 0);
static AP_HAL::Semaphore *get_semaphore(uint16_t bus);

View File

@ -77,7 +77,7 @@ void Scheduler::_create_realtime_thread(pthread_t *ctx, int rtprio,
}
}
void Scheduler::init(void* machtnichts)
void Scheduler::init()
{
mlockall(MCL_CURRENT|MCL_FUTURE);

View File

@ -23,7 +23,7 @@ public:
return static_cast<Scheduler*>(scheduler);
}
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

@ -25,7 +25,7 @@ public:
return static_cast<Storage*>(storage);
}
void init(void* machtnichts) {}
void init() {}
uint8_t read_byte(uint16_t loc);
uint16_t read_word(uint16_t loc);
uint32_t read_dword(uint16_t loc);