mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-19 14:23:57 -04:00
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:
parent
0c3733601b
commit
4c82c535cc
@ -55,7 +55,7 @@ void ADCSource::set_pin(uint8_t pin) {
|
||||
_pin = pin;
|
||||
}
|
||||
|
||||
void SITLAnalogIn::init(void *ap_hal_scheduler) {
|
||||
void SITLAnalogIn::init() {
|
||||
}
|
||||
|
||||
AP_HAL::AnalogSource* SITLAnalogIn::channel(int16_t pin) {
|
||||
|
@ -37,7 +37,7 @@ public:
|
||||
SITLAnalogIn(SITL_State *sitlState) {
|
||||
_sitlState = sitlState;
|
||||
}
|
||||
void init(void* ap_hal_scheduler);
|
||||
void init();
|
||||
AP_HAL::AnalogSource* channel(int16_t n);
|
||||
float board_voltage(void) {
|
||||
return 5.0f;
|
||||
|
@ -71,16 +71,16 @@ void HAL_SITL::run(int argc, char * const argv[], Callbacks* callbacks) const
|
||||
assert(callbacks);
|
||||
|
||||
_sitl_state->init(argc, argv);
|
||||
scheduler->init(NULL);
|
||||
scheduler->init();
|
||||
uartA->begin(115200);
|
||||
|
||||
rcin->init(NULL);
|
||||
rcout->init(NULL);
|
||||
rcin->init();
|
||||
rcout->init();
|
||||
|
||||
//spi->init(NULL);
|
||||
//spi->init();
|
||||
//i2c->begin();
|
||||
//i2c->setTimeout(100);
|
||||
analogin->init(NULL);
|
||||
analogin->init();
|
||||
|
||||
callbacks->setup();
|
||||
scheduler->system_initialized();
|
||||
|
@ -7,7 +7,7 @@ using namespace HALSITL;
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
void SITLRCInput::init(void* machtnichts)
|
||||
void SITLRCInput::init()
|
||||
{
|
||||
clear_overrides();
|
||||
}
|
||||
|
@ -11,7 +11,7 @@ public:
|
||||
SITLRCInput(SITL_State *sitlState) {
|
||||
_sitlState = sitlState;
|
||||
}
|
||||
void init(void* machtnichts);
|
||||
void init();
|
||||
bool new_input();
|
||||
uint8_t num_channels() {
|
||||
return 8;
|
||||
|
@ -5,7 +5,7 @@
|
||||
|
||||
using namespace HALSITL;
|
||||
|
||||
void SITLRCOutput::init(void* machtnichts) {}
|
||||
void SITLRCOutput::init() {}
|
||||
|
||||
void SITLRCOutput::set_freq(uint32_t chmask, uint16_t freq_hz) {
|
||||
_freq_hz = freq_hz;
|
||||
|
@ -12,7 +12,7 @@ public:
|
||||
_sitlState = sitlState;
|
||||
_freq_hz = 50;
|
||||
}
|
||||
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);
|
||||
|
@ -33,7 +33,7 @@ SITLScheduler::SITLScheduler(SITL_State *sitlState) :
|
||||
{
|
||||
}
|
||||
|
||||
void SITLScheduler::init(void *unused)
|
||||
void SITLScheduler::init()
|
||||
{
|
||||
}
|
||||
|
||||
|
@ -19,7 +19,7 @@ public:
|
||||
|
||||
/* 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);
|
||||
|
@ -11,7 +11,7 @@ public:
|
||||
SITLEEPROMStorage() {
|
||||
_eeprom_fd = -1;
|
||||
}
|
||||
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);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user