mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_DAL: call start_frame for all backends
This commit is contained in:
parent
96060ef31e
commit
dd539f8ec9
@ -79,7 +79,7 @@ void AP_DAL_RangeFinder::start_frame()
|
|||||||
for (uint8_t i=0; i<_RRNH.num_sensors; i++) {
|
for (uint8_t i=0; i<_RRNH.num_sensors; i++) {
|
||||||
auto *backend = rangefinder->get_backend(i);
|
auto *backend = rangefinder->get_backend(i);
|
||||||
if (backend == nullptr) {
|
if (backend == nullptr) {
|
||||||
break;
|
continue;
|
||||||
}
|
}
|
||||||
_backend[i]->start_frame(backend);
|
_backend[i]->start_frame(backend);
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user