mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-09 08:04:14 -03:00
HAL_PX4: Storage::_timer_tick is an override
This commit is contained in:
parent
26161ee467
commit
0f079deebf
@ -407,7 +407,7 @@ void *PX4Scheduler::_storage_thread(void *arg)
|
|||||||
|
|
||||||
// process any pending storage writes
|
// process any pending storage writes
|
||||||
perf_begin(sched->_perf_storage_timer);
|
perf_begin(sched->_perf_storage_timer);
|
||||||
((PX4Storage *)hal.storage)->_timer_tick();
|
hal.storage->_timer_tick();
|
||||||
perf_end(sched->_perf_storage_timer);
|
perf_end(sched->_perf_storage_timer);
|
||||||
}
|
}
|
||||||
return nullptr;
|
return nullptr;
|
||||||
|
@ -35,7 +35,7 @@ public:
|
|||||||
void read_block(void *dst, uint16_t src, size_t n);
|
void read_block(void *dst, uint16_t src, size_t n);
|
||||||
void write_block(uint16_t dst, const void* src, size_t n);
|
void write_block(uint16_t dst, const void* src, size_t n);
|
||||||
|
|
||||||
void _timer_tick(void);
|
void _timer_tick(void) override;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
volatile bool _initialised;
|
volatile bool _initialised;
|
||||||
|
Loading…
Reference in New Issue
Block a user