mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
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:
parent
934d05f4ff
commit
22ce90af34
@ -188,6 +188,18 @@ bool AP_RPM::enabled(uint8_t instance) const
|
|||||||
return true;
|
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
|
// singleton instance
|
||||||
AP_RPM *AP_RPM::_singleton;
|
AP_RPM *AP_RPM::_singleton;
|
||||||
|
|
||||||
|
@ -75,12 +75,7 @@ public:
|
|||||||
/*
|
/*
|
||||||
return RPM for a sensor. Return -1 if not healthy
|
return RPM for a sensor. Return -1 if not healthy
|
||||||
*/
|
*/
|
||||||
float get_rpm(uint8_t instance) const {
|
bool get_rpm(uint8_t instance, float &rpm_value) const;
|
||||||
if (!healthy(instance)) {
|
|
||||||
return -1;
|
|
||||||
}
|
|
||||||
return state[instance].rate_rpm;
|
|
||||||
}
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
return signal quality for a sensor.
|
return signal quality for a sensor.
|
||||||
|
@ -56,9 +56,11 @@ void loop(void)
|
|||||||
sensor_state = '-';
|
sensor_state = '-';
|
||||||
}
|
}
|
||||||
|
|
||||||
|
float rpm = -1;
|
||||||
|
RPM.get_rpm(ii, rpm);
|
||||||
hal.console->printf("%u - (%c) RPM: %8.2f Quality: %.2f ",
|
hal.console->printf("%u - (%c) RPM: %8.2f Quality: %.2f ",
|
||||||
ii, sensor_state,
|
ii, sensor_state,
|
||||||
(double)RPM.get_rpm(ii),
|
(double)rpm,
|
||||||
(double)RPM.get_signal_quality(ii));
|
(double)RPM.get_signal_quality(ii));
|
||||||
|
|
||||||
if (ii+1 < RPM.num_sensors()) {
|
if (ii+1 < RPM.num_sensors()) {
|
||||||
|
Loading…
Reference in New Issue
Block a user