mirror of https://github.com/ArduPilot/ardupilot
AP_RPM: Whitespace changes
This commit is contained in:
parent
5bb4729d61
commit
df1280e999
|
@ -22,7 +22,7 @@ class AP_RPM_Backend
|
|||
{
|
||||
public:
|
||||
// constructor. This incorporates initialisation as well.
|
||||
AP_RPM_Backend(AP_RPM &_ap_rpm, uint8_t instance, AP_RPM::RPM_State &_state);
|
||||
AP_RPM_Backend(AP_RPM &_ap_rpm, uint8_t instance, AP_RPM::RPM_State &_state);
|
||||
|
||||
// we declare a virtual destructor so that RPM drivers can
|
||||
// override with a custom destructor if need be
|
||||
|
@ -37,7 +37,7 @@ public:
|
|||
}
|
||||
return ap_rpm._params[state.instance].pin.get();
|
||||
}
|
||||
|
||||
|
||||
protected:
|
||||
|
||||
AP_RPM &ap_rpm;
|
||||
|
|
|
@ -88,7 +88,7 @@ void AP_RPM_Pin::update(void)
|
|||
float filter_value = signal_quality_filter.get();
|
||||
|
||||
state.rate_rpm = signal_quality_filter.apply(rpm);
|
||||
|
||||
|
||||
if ((maximum <= 0 || rpm <= maximum) && (rpm >= minimum)) {
|
||||
if (is_zero(filter_value)){
|
||||
quality = 0;
|
||||
|
@ -102,7 +102,7 @@ void AP_RPM_Pin::update(void)
|
|||
}
|
||||
state.signal_quality = (0.1 * quality) + (0.9 * state.signal_quality);
|
||||
}
|
||||
|
||||
|
||||
// assume we get readings at at least 1Hz, otherwise reset quality to zero
|
||||
if (AP_HAL::millis() - state.last_reading_ms > 1000) {
|
||||
state.signal_quality = 0;
|
||||
|
|
Loading…
Reference in New Issue