mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
HAL_PX4: fixed functor comparison with NULL
This commit is contained in:
parent
0daeeb9518
commit
43fb1202f2
@ -255,7 +255,7 @@ void PX4Scheduler::_run_timers(bool called_from_timer_thread)
|
||||
if (!_timer_suspended) {
|
||||
// now call the timer based drivers
|
||||
for (int i = 0; i < _num_timer_procs; i++) {
|
||||
if (_timer_proc[i] != NULL) {
|
||||
if (_timer_proc[i]) {
|
||||
_timer_proc[i]();
|
||||
}
|
||||
}
|
||||
@ -315,7 +315,7 @@ void PX4Scheduler::_run_io(void)
|
||||
if (!_timer_suspended) {
|
||||
// now call the IO based drivers
|
||||
for (int i = 0; i < _num_io_procs; i++) {
|
||||
if (_io_proc[i] != NULL) {
|
||||
if (_io_proc[i]) {
|
||||
_io_proc[i]();
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user