AP_RangeFinder: remove unused voltage_mv_orient method

This is really backend-specific data and shouldn't be exposed
This commit is contained in:
Peter Barker 2020-12-05 11:20:26 +11:00 committed by Andrew Tridgell
parent 97cbf17d01
commit 1c57eed66c
2 changed files with 0 additions and 10 deletions

View File

@ -660,15 +660,6 @@ uint16_t RangeFinder::distance_cm_orient(enum Rotation orientation) const
return backend->distance_cm();
}
uint16_t RangeFinder::voltage_mv_orient(enum Rotation orientation) const
{
AP_RangeFinder_Backend *backend = find_instance(orientation);
if (backend == nullptr) {
return 0;
}
return backend->voltage_mv();
}
int16_t RangeFinder::max_distance_cm_orient(enum Rotation orientation) const
{
AP_RangeFinder_Backend *backend = find_instance(orientation);

View File

@ -170,7 +170,6 @@ public:
// methods to return a distance on a particular orientation from
// any sensor which can current supply it
uint16_t distance_cm_orient(enum Rotation orientation) const;
uint16_t voltage_mv_orient(enum Rotation orientation) const;
int16_t max_distance_cm_orient(enum Rotation orientation) const;
int16_t min_distance_cm_orient(enum Rotation orientation) const;
int16_t ground_clearance_cm_orient(enum Rotation orientation) const;