mirror of https://github.com/ArduPilot/ardupilot
AP_Scheduler: fixed _last_run initialisation
another valgrind bug
This commit is contained in:
parent
0a25d6220a
commit
02bd24cf57
|
@ -32,7 +32,8 @@ void AP_Scheduler::init(const AP_Scheduler::Task *tasks, uint8_t num_tasks)
|
|||
_tasks = tasks;
|
||||
_num_tasks = num_tasks;
|
||||
_last_run = new uint16_t[_num_tasks];
|
||||
memset(_last_run, 0, sizeof(_last_run[0]*_num_tasks));
|
||||
memset(_last_run, 0, sizeof(_last_run[0]) * _num_tasks);
|
||||
_tick_counter = 0;
|
||||
}
|
||||
|
||||
// one tick has passed
|
||||
|
|
Loading…
Reference in New Issue