AP_HAL_SITL: Do not compare delegate to NULL

Use the simpler "if (delegate_name)" since it allows simpler
implementation in the class, i.e. the bool operator rather than having
to compare to another object.
This commit is contained in:
Lucas De Marchi 2015-05-24 07:40:10 -03:00 committed by Andrew Tridgell
parent 9ef870c08a
commit acdcdc35fa
1 changed files with 2 additions and 2 deletions

View File

@ -221,7 +221,7 @@ void SITLScheduler::_run_timer_procs(bool called_from_isr)
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]();
}
}
@ -247,7 +247,7 @@ void SITLScheduler::_run_io_procs(bool called_from_isr)
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]();
}
}