mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_RangeFinder: change get_signal_quality signature to use int8_t
This commit is contained in:
parent
dfe6c21ea5
commit
7953cd9a89
@ -74,7 +74,7 @@ public:
|
||||
|
||||
// 0 is no return value, 100 is perfect. false means signal
|
||||
// quality is not available
|
||||
virtual bool get_signal_quality_pct(uint8_t &quality_pct) const { return false; }
|
||||
virtual bool get_signal_quality_pct(int8_t &quality_pct) const { return false; }
|
||||
|
||||
// return the actual type of the rangefinder, as opposed to the
|
||||
// parameter value which may be changed at runtime.
|
||||
|
@ -26,7 +26,7 @@ protected:
|
||||
return MAV_DISTANCE_SENSOR_LASER;
|
||||
}
|
||||
|
||||
bool get_signal_quality_pct(uint8_t &quality_pct) const override {
|
||||
bool get_signal_quality_pct(int8_t &quality_pct) const override {
|
||||
quality_pct = no_signal ? 0 : 100;
|
||||
return true;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user