AP_RangeFinder: change get_signal_quality signature to use int8_t

This commit is contained in:
Willian Galvani 2023-08-18 12:24:47 -03:00 committed by Peter Barker
parent dfe6c21ea5
commit 7953cd9a89
2 changed files with 2 additions and 2 deletions

View File

@ -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.

View File

@ -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;
}