AP_DAL: call start_frame for all backends

This commit is contained in:
Tatsuya Yamaguchi 2022-12-17 21:48:54 +09:00 committed by Peter Barker
parent 96060ef31e
commit dd539f8ec9
1 changed files with 1 additions and 1 deletions

View File

@ -79,7 +79,7 @@ void AP_DAL_RangeFinder::start_frame()
for (uint8_t i=0; i<_RRNH.num_sensors; i++) {
auto *backend = rangefinder->get_backend(i);
if (backend == nullptr) {
break;
continue;
}
_backend[i]->start_frame(backend);
}