AP_RangeFinder: implement distance_cm_orient in terms of distance_orient

This commit is contained in:
Peter Barker 2022-04-18 15:50:50 +10:00 committed by Andrew Tridgell
parent d7d7574d2e
commit cef436b272

View File

@ -686,11 +686,7 @@ float RangeFinder::distance_orient(enum Rotation orientation) const
uint16_t RangeFinder::distance_cm_orient(enum Rotation orientation) const
{
AP_RangeFinder_Backend *backend = find_instance(orientation);
if (backend == nullptr) {
return 0;
}
return backend->distance_cm();
return distance_orient(orientation) * 100.0;
}
int16_t RangeFinder::max_distance_cm_orient(enum Rotation orientation) const