AP_RPM: changed get_rpm() API to be scripting compatible

return a bool and use a reference for the value
This commit is contained in:
Andrew Tridgell 2020-03-06 10:46:27 +11:00
parent 934d05f4ff
commit 22ce90af34
3 changed files with 16 additions and 7 deletions

View File

@ -188,6 +188,18 @@ bool AP_RPM::enabled(uint8_t instance) const
return true;
}
/*
get RPM value, return true on success
*/
bool AP_RPM::get_rpm(uint8_t instance, float &rpm_value) const
{
if (!healthy(instance)) {
return false;
}
rpm_value = state[instance].rate_rpm;
return true;
}
// singleton instance
AP_RPM *AP_RPM::_singleton;

View File

@ -75,12 +75,7 @@ public:
/*
return RPM for a sensor. Return -1 if not healthy
*/
float get_rpm(uint8_t instance) const {
if (!healthy(instance)) {
return -1;
}
return state[instance].rate_rpm;
}
bool get_rpm(uint8_t instance, float &rpm_value) const;
/*
return signal quality for a sensor.

View File

@ -56,9 +56,11 @@ void loop(void)
sensor_state = '-';
}
float rpm = -1;
RPM.get_rpm(ii, rpm);
hal.console->printf("%u - (%c) RPM: %8.2f Quality: %.2f ",
ii, sensor_state,
(double)RPM.get_rpm(ii),
(double)rpm,
(double)RPM.get_signal_quality(ii));
if (ii+1 < RPM.num_sensors()) {