mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AP_RangeFinder: remove unused voltage_mv_orient method
This is really backend-specific data and shouldn't be exposed
This commit is contained in:
parent
97cbf17d01
commit
1c57eed66c
@ -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);
|
||||
|
@ -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;
|
||||
|
Loading…
Reference in New Issue
Block a user