mirror of https://github.com/ArduPilot/ardupilot
AP_ICEngine: added ICE_STARTCHN_MIN
this gives a min PWM value to trigger an engine stop. It makes RC glitches leading to engine stop much less likely
This commit is contained in:
parent
54c827a792
commit
890fc96d20
|
@ -134,7 +134,14 @@ const AP_Param::GroupInfo AP_ICEngine::var_info[] = {
|
|||
// @Description: Options for ICE control
|
||||
// @Bitmask: 0:DisableIgnitionRCFailsafe
|
||||
AP_GROUPINFO("OPTIONS", 15, AP_ICEngine, options, 0),
|
||||
|
||||
|
||||
// @Param: STARTCHN_MIN
|
||||
// @DisplayName: Input channel for engine start minimum PWM
|
||||
// @Description: This is a minimum PWM value for engine start channel for an engine stop to be commanded. Setting this value will avoid RC input glitches with low PWM values from causing an unwanted engine stop. A value of zero means any PWM below 1300 triggers an engine stop.
|
||||
// @User: Standard
|
||||
// @Range: 0 1300
|
||||
AP_GROUPINFO("STARTCHN_MIN", 16, AP_ICEngine, start_chan_min_pwm, 0),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -166,6 +173,10 @@ void AP_ICEngine::update(void)
|
|||
// get starter control channel
|
||||
cvalue = c->get_radio_in();
|
||||
|
||||
if (cvalue < start_chan_min_pwm) {
|
||||
cvalue = start_chan_last_value;
|
||||
}
|
||||
|
||||
// snap the input to either 1000, 1500, or 2000
|
||||
// this is useful to compare a debounce changed value
|
||||
// while ignoring tiny noise
|
||||
|
@ -348,7 +359,8 @@ bool AP_ICEngine::engine_control(float start_control, float cold_start, float he
|
|||
RC_Channel *c = rc().channel(start_chan-1);
|
||||
if (c != nullptr) {
|
||||
// get starter control channel
|
||||
if (c->get_radio_in() <= 1300) {
|
||||
uint16_t cvalue = c->get_radio_in();
|
||||
if (cvalue >= start_chan_min_pwm && cvalue <= 1300) {
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Engine: start control disabled");
|
||||
return false;
|
||||
}
|
||||
|
|
|
@ -66,6 +66,9 @@ private:
|
|||
// channel for pilot to command engine start, 0 for none
|
||||
AP_Int8 start_chan;
|
||||
|
||||
// min pwm on start channel for engine stop
|
||||
AP_Int16 start_chan_min_pwm;
|
||||
|
||||
// which RPM instance to use
|
||||
AP_Int8 rpm_instance;
|
||||
|
||||
|
|
Loading…
Reference in New Issue