Browse Source

AP_HAL_FLYMAPLE: use init() method without arguments

Override the init() method from parent class that doesn't have a
parameter since it's not used here.
mission-4.1.18
Lucas De Marchi 9 years ago
parent
commit
0514aadaec
  1. 2
      libraries/AP_HAL_FLYMAPLE/AnalogIn.cpp
  2. 2
      libraries/AP_HAL_FLYMAPLE/AnalogIn.h
  3. 12
      libraries/AP_HAL_FLYMAPLE/HAL_FLYMAPLE_Class.cpp
  4. 2
      libraries/AP_HAL_FLYMAPLE/RCInput.cpp
  5. 2
      libraries/AP_HAL_FLYMAPLE/RCInput.h
  6. 2
      libraries/AP_HAL_FLYMAPLE/RCOutput.cpp
  7. 2
      libraries/AP_HAL_FLYMAPLE/RCOutput.h
  8. 2
      libraries/AP_HAL_FLYMAPLE/SPIDriver.cpp
  9. 2
      libraries/AP_HAL_FLYMAPLE/SPIDriver.h
  10. 2
      libraries/AP_HAL_FLYMAPLE/Scheduler.cpp
  11. 2
      libraries/AP_HAL_FLYMAPLE/Scheduler.h
  12. 2
      libraries/AP_HAL_FLYMAPLE/Storage.cpp
  13. 2
      libraries/AP_HAL_FLYMAPLE/Storage.h

2
libraries/AP_HAL_FLYMAPLE/AnalogIn.cpp

@ -36,7 +36,7 @@ FLYMAPLEAnalogIn::FLYMAPLEAnalogIn() : @@ -36,7 +36,7 @@ FLYMAPLEAnalogIn::FLYMAPLEAnalogIn() :
_vcc(FLYMAPLEAnalogSource(ANALOG_INPUT_BOARD_VCC))
{}
void FLYMAPLEAnalogIn::init(void* machtnichts) {
void FLYMAPLEAnalogIn::init() {
/* Register FLYMAPLEAnalogIn::_timer_event with the scheduler. */
hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&FLYMAPLEAnalogIn::_timer_event, void));
/* Register each private channel with FLYMAPLEAnalogIn. */

2
libraries/AP_HAL_FLYMAPLE/AnalogIn.h

@ -82,7 +82,7 @@ private: @@ -82,7 +82,7 @@ private:
class AP_HAL_FLYMAPLE_NS::FLYMAPLEAnalogIn : public AP_HAL::AnalogIn {
public:
FLYMAPLEAnalogIn();
void init(void* implspecific);
void init();
AP_HAL::AnalogSource* channel(int16_t n);
float board_voltage(void);

12
libraries/AP_HAL_FLYMAPLE/HAL_FLYMAPLE_Class.cpp

@ -73,19 +73,19 @@ void HAL_FLYMAPLE::run(int argc, char* const argv[], Callbacks* callbacks) const @@ -73,19 +73,19 @@ void HAL_FLYMAPLE::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 is the serial port used for the console, so lets make sure
* it is initialized at boot */
uartA->begin(115200);
rcin->init(NULL);
rcout->init(NULL);
spi->init(NULL);
rcin->init();
rcout->init();
spi->init();
i2c->begin();
i2c->setTimeout(100);
analogin->init(NULL);
storage->init(NULL); // Uses EEPROM.*, flash_stm* copied from AeroQuad_v3.2
analogin->init();
storage->init(); // Uses EEPROM.*, flash_stm* copied from AeroQuad_v3.2
callbacks->setup();
scheduler->system_initialized();

2
libraries/AP_HAL_FLYMAPLE/RCInput.cpp

@ -106,7 +106,7 @@ void FLYMAPLERCInput::_timer_capt_cb(void) @@ -106,7 +106,7 @@ void FLYMAPLERCInput::_timer_capt_cb(void)
previous_count = current_count;
}
void FLYMAPLERCInput::init(void* machtnichts)
void FLYMAPLERCInput::init()
{
/* initialize overrides */
clear_overrides();

2
libraries/AP_HAL_FLYMAPLE/RCInput.h

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

2
libraries/AP_HAL_FLYMAPLE/RCOutput.cpp

@ -31,7 +31,7 @@ extern const AP_HAL::HAL& hal; @@ -31,7 +31,7 @@ extern const AP_HAL::HAL& hal;
#define MAX_OVERFLOW ((1 << 16) - 1)
void FLYMAPLERCOutput::init(void* machtnichts) {}
void FLYMAPLERCOutput::init() {}
void FLYMAPLERCOutput::set_freq(uint32_t chmask, uint16_t freq_hz)
{

2
libraries/AP_HAL_FLYMAPLE/RCOutput.h

@ -24,7 +24,7 @@ @@ -24,7 +24,7 @@
#define FLYMAPLE_RC_OUTPUT_NUM_CHANNELS 6
class AP_HAL_FLYMAPLE_NS::FLYMAPLERCOutput : 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);

2
libraries/AP_HAL_FLYMAPLE/SPIDriver.cpp

@ -89,7 +89,7 @@ FLYMAPLESPIDeviceManager::FLYMAPLESPIDeviceManager() @@ -89,7 +89,7 @@ FLYMAPLESPIDeviceManager::FLYMAPLESPIDeviceManager()
{
}
void FLYMAPLESPIDeviceManager::init(void *)
void FLYMAPLESPIDeviceManager::init()
{
}

2
libraries/AP_HAL_FLYMAPLE/SPIDriver.h

@ -42,7 +42,7 @@ private: @@ -42,7 +42,7 @@ private:
class AP_HAL_FLYMAPLE_NS::FLYMAPLESPIDeviceManager : public AP_HAL::SPIDeviceManager {
public:
FLYMAPLESPIDeviceManager();
void init(void *);
void init();
AP_HAL::SPIDeviceDriver* device(enum AP_HAL::SPIDevice, uint8_t index);
private:
FLYMAPLESPIDeviceDriver _device;

2
libraries/AP_HAL_FLYMAPLE/Scheduler.cpp

@ -53,7 +53,7 @@ FLYMAPLEScheduler::FLYMAPLEScheduler() : @@ -53,7 +53,7 @@ FLYMAPLEScheduler::FLYMAPLEScheduler() :
_initialized(false)
{}
void FLYMAPLEScheduler::init(void* machtnichts)
void FLYMAPLEScheduler::init()
{
delay_us(2000000); // Wait for startup so we have time to connect a new USB console
// 1kHz interrupts from systick for normal timers

2
libraries/AP_HAL_FLYMAPLE/Scheduler.h

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

2
libraries/AP_HAL_FLYMAPLE/Storage.cpp

@ -58,7 +58,7 @@ static EEPROMClass eeprom[num_eeprom_blocks]; @@ -58,7 +58,7 @@ static EEPROMClass eeprom[num_eeprom_blocks];
FLYMAPLEStorage::FLYMAPLEStorage()
{}
void FLYMAPLEStorage::init(void*)
void FLYMAPLEStorage::init()
{
for (int i = 0; i < num_eeprom_blocks; i++)
{

2
libraries/AP_HAL_FLYMAPLE/Storage.h

@ -24,7 +24,7 @@ @@ -24,7 +24,7 @@
class AP_HAL_FLYMAPLE_NS::FLYMAPLEStorage : public AP_HAL::Storage {
public:
FLYMAPLEStorage();
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);

Loading…
Cancel
Save