mirror of https://github.com/ArduPilot/ardupilot
AP_Scheduler: added current_task static
will be used to debug stuck tasks on PX4
This commit is contained in:
parent
bdd9fe77c7
commit
67f5ba0b94
|
@ -26,6 +26,8 @@
|
|||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
int8_t AP_Scheduler::current_task = -1;
|
||||
|
||||
const AP_Param::GroupInfo AP_Scheduler::var_info[] PROGMEM = {
|
||||
// @Param: DEBUG
|
||||
// @DisplayName: Scheduler debug level
|
||||
|
@ -83,7 +85,9 @@ void AP_Scheduler::run(uint16_t time_available)
|
|||
// run it
|
||||
_task_time_started = now;
|
||||
task_fn_t func = (task_fn_t)pgm_read_pointer(&_tasks[i].function);
|
||||
current_task = i;
|
||||
func();
|
||||
current_task = -1;
|
||||
|
||||
// record the tick counter when we ran. This drives
|
||||
// when we next run the event
|
||||
|
|
|
@ -70,6 +70,9 @@ public:
|
|||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
// current running task, or -1 if none. Used to debug stuck tasks
|
||||
static int8_t current_task;
|
||||
|
||||
private:
|
||||
// used to enable scheduler debugging
|
||||
AP_Int8 _debug;
|
||||
|
|
Loading…
Reference in New Issue