mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 12:14:10 -04:00
AP_RPM: Add Minimum Quality Parameter
This commit is contained in:
parent
1f8b90e876
commit
fd106b20c7
@ -46,6 +46,12 @@ const AP_Param::GroupInfo AP_RPM::var_info[] = {
|
|||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
AP_GROUPINFO("_MIN", 3, AP_RPM, _minimum[0], 0),
|
AP_GROUPINFO("_MIN", 3, AP_RPM, _minimum[0], 0),
|
||||||
|
|
||||||
|
// @Param: _MIN_QUAL
|
||||||
|
// @DisplayName: Minimum Quality
|
||||||
|
// @Description: Minimum data quality to be used
|
||||||
|
// @Increment: 0.1
|
||||||
|
AP_GROUPINFO("_MIN_QUAL", 4, AP_RPM, _quality_min[0], 0.5),
|
||||||
|
|
||||||
#if RPM_MAX_INSTANCES > 1
|
#if RPM_MAX_INSTANCES > 1
|
||||||
// @Param: 2_TYPE
|
// @Param: 2_TYPE
|
||||||
// @DisplayName: Second RPM type
|
// @DisplayName: Second RPM type
|
||||||
@ -133,6 +139,12 @@ bool AP_RPM::healthy(uint8_t instance) const
|
|||||||
if (AP_HAL::millis() - state[instance].last_reading_ms > 1000) {
|
if (AP_HAL::millis() - state[instance].last_reading_ms > 1000) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// check that data quality is above minimum required
|
||||||
|
if (state[instance].signal_quality < _quality_min[0]) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -53,6 +53,7 @@ public:
|
|||||||
AP_Float _scaling[RPM_MAX_INSTANCES];
|
AP_Float _scaling[RPM_MAX_INSTANCES];
|
||||||
AP_Float _maximum[RPM_MAX_INSTANCES];
|
AP_Float _maximum[RPM_MAX_INSTANCES];
|
||||||
AP_Float _minimum[RPM_MAX_INSTANCES];
|
AP_Float _minimum[RPM_MAX_INSTANCES];
|
||||||
|
AP_Float _quality_min[RPM_MAX_INSTANCES];
|
||||||
|
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user