mirror of https://github.com/ArduPilot/ardupilot
AP_RPM: added RPM_MAX parameter
attempt to avoid noise in the pulses
This commit is contained in:
parent
e3f7b002c2
commit
ac363c5447
|
@ -33,6 +33,12 @@ const AP_Param::GroupInfo AP_RPM::var_info[] PROGMEM = {
|
|||
// @Increment: 0.001
|
||||
AP_GROUPINFO("_SCALING", 1, AP_RPM, _scaling[0], 1.0f),
|
||||
|
||||
// @Param: _MAX
|
||||
// @DisplayName: Maximum RPM
|
||||
// @Description: Maximum RPM to report
|
||||
// @Increment: 1
|
||||
AP_GROUPINFO("_MAX", 2, AP_RPM, _maximum[0], 0),
|
||||
|
||||
#if RPM_MAX_INSTANCES > 1
|
||||
// @Param: 2_TYPE
|
||||
// @DisplayName: Second RPM type
|
||||
|
|
|
@ -50,6 +50,7 @@ public:
|
|||
// parameters for each instance
|
||||
AP_Int8 _type[RPM_MAX_INSTANCES];
|
||||
AP_Float _scaling[RPM_MAX_INSTANCES];
|
||||
AP_Float _maximum[RPM_MAX_INSTANCES];
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
|
|
|
@ -34,12 +34,6 @@
|
|||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
/*
|
||||
don't accept periods below 100us as it is probably ringing of the
|
||||
signal. It would represent 600k RPM
|
||||
*/
|
||||
#define RPM_MIN_PERIOD_US 100
|
||||
|
||||
/*
|
||||
open the sensor in constructor
|
||||
*/
|
||||
|
@ -85,14 +79,19 @@ void AP_RPM_PX4_PWM::update(void)
|
|||
|
||||
while (::read(_fd, &pwm, sizeof(pwm)) == sizeof(pwm)) {
|
||||
// the px4 pwm_input driver reports the period in microseconds
|
||||
if (pwm.period > RPM_MIN_PERIOD_US) {
|
||||
sum += (1.0e6f * 60) / pwm.period;
|
||||
if (pwm.period == 0) {
|
||||
continue;
|
||||
}
|
||||
float rpm = scaling * (1.0e6f * 60) / pwm.period;
|
||||
float maximum = ap_rpm._maximum[state.instance];
|
||||
if (maximum <= 0 || rpm <= maximum) {
|
||||
sum += rpm;
|
||||
count++;
|
||||
}
|
||||
}
|
||||
|
||||
if (count != 0) {
|
||||
state.rate_rpm = scaling * sum / count;
|
||||
state.rate_rpm = sum / count;
|
||||
state.last_reading_ms = hal.scheduler->millis();
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue