mirror of https://github.com/ArduPilot/ardupilot
AP_Scheduler: added ticks32() API
this is the number of scheduler ticks since boot, as uint32_t
This commit is contained in:
parent
9fddec28d3
commit
5f6d3e5d8c
|
@ -154,6 +154,7 @@ void AP_Scheduler::init(const AP_Scheduler::Task *tasks, uint8_t num_tasks, uint
|
||||||
void AP_Scheduler::tick(void)
|
void AP_Scheduler::tick(void)
|
||||||
{
|
{
|
||||||
_tick_counter++;
|
_tick_counter++;
|
||||||
|
_tick_counter32++;
|
||||||
}
|
}
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
|
|
|
@ -123,6 +123,7 @@ public:
|
||||||
|
|
||||||
// return current tick counter
|
// return current tick counter
|
||||||
uint16_t ticks() const { return _tick_counter; }
|
uint16_t ticks() const { return _tick_counter; }
|
||||||
|
uint32_t ticks32() const { return _tick_counter32; }
|
||||||
|
|
||||||
// run the tasks. Call this once per 'tick'.
|
// run the tasks. Call this once per 'tick'.
|
||||||
// time_available is the amount of time available to run
|
// time_available is the amount of time available to run
|
||||||
|
@ -224,6 +225,7 @@ private:
|
||||||
// number of 'ticks' that have passed (number of times that
|
// number of 'ticks' that have passed (number of times that
|
||||||
// tick() has been called
|
// tick() has been called
|
||||||
uint16_t _tick_counter;
|
uint16_t _tick_counter;
|
||||||
|
uint32_t _tick_counter32;
|
||||||
|
|
||||||
// tick counter at the time we last ran each task
|
// tick counter at the time we last ran each task
|
||||||
uint16_t *_last_run;
|
uint16_t *_last_run;
|
||||||
|
|
Loading…
Reference in New Issue