mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-12 01:23:56 -03:00
AP_ICEngine: fully move to aux function removing dedicated min PWM and high low thresholds
This commit is contained in:
parent
cc0f3f2915
commit
9185430797
@ -30,8 +30,6 @@
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
#define AP_ICENGINE_START_CHAN_DEBOUNCE_MS 300
|
||||
|
||||
const AP_Param::GroupInfo AP_ICEngine::var_info[] = {
|
||||
|
||||
// @Param: ENABLE
|
||||
@ -163,7 +161,8 @@ const AP_Param::GroupInfo AP_ICEngine::var_info[] = {
|
||||
// @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 above 800 and below 1300 triggers an engine stop. To stop the engine start channel must above the larger of this value and 800 and below 1300.
|
||||
// @User: Standard
|
||||
// @Range: 0 1300
|
||||
AP_GROUPINFO("STARTCHN_MIN", 16, AP_ICEngine, start_chan_min_pwm, 0),
|
||||
|
||||
// 16 was STARTCHN_MIN
|
||||
|
||||
#if AP_RPM_ENABLED
|
||||
// @Param: REDLINE_RPM
|
||||
@ -282,6 +281,12 @@ void AP_ICEngine::param_conversion()
|
||||
}
|
||||
}
|
||||
|
||||
// Handle incoming aux function
|
||||
void AP_ICEngine::do_aux_function(const RC_Channel::AuxSwitchPos ch_flag)
|
||||
{
|
||||
aux_pos = ch_flag;
|
||||
}
|
||||
|
||||
/*
|
||||
update engine state
|
||||
*/
|
||||
@ -291,51 +296,20 @@ void AP_ICEngine::update(void)
|
||||
return;
|
||||
}
|
||||
|
||||
uint16_t cvalue = 1500;
|
||||
RC_Channel *c = rc().find_channel_for_option(RC_Channel::AUX_FUNC::ICE_START_STOP);
|
||||
if (c != nullptr && rc().has_valid_input()) {
|
||||
// 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
|
||||
if (cvalue >= RC_Channel::AUX_PWM_TRIGGER_HIGH) {
|
||||
cvalue = 2000;
|
||||
} else if ((cvalue > 800) && (cvalue <= RC_Channel::AUX_PWM_TRIGGER_LOW)) {
|
||||
cvalue = 1300;
|
||||
} else {
|
||||
cvalue = 1500;
|
||||
}
|
||||
}
|
||||
|
||||
bool should_run = false;
|
||||
uint32_t now = AP_HAL::millis();
|
||||
|
||||
|
||||
// debounce timer to protect from spurious changes on start_chan rc input
|
||||
// If the cached value is the same, reset timer
|
||||
if (start_chan_last_value == cvalue) {
|
||||
start_chan_last_ms = now;
|
||||
} else if (now - start_chan_last_ms >= AP_ICENGINE_START_CHAN_DEBOUNCE_MS) {
|
||||
// if it has changed, and stayed changed for the duration, then use that new value
|
||||
start_chan_last_value = cvalue;
|
||||
}
|
||||
|
||||
if (state == ICE_START_HEIGHT_DELAY && start_chan_last_value >= RC_Channel::AUX_PWM_TRIGGER_HIGH) {
|
||||
if ((state == ICE_START_HEIGHT_DELAY) && (aux_pos == RC_Channel::AuxSwitchPos::HIGH)) {
|
||||
// user is overriding the height start delay and asking for
|
||||
// immediate start. Put into ICE_OFF so that the logic below
|
||||
// can start the engine now
|
||||
state = ICE_OFF;
|
||||
}
|
||||
|
||||
if (state == ICE_OFF && start_chan_last_value >= RC_Channel::AUX_PWM_TRIGGER_HIGH) {
|
||||
if ((state == ICE_OFF) && (aux_pos == RC_Channel::AuxSwitchPos::HIGH)) {
|
||||
should_run = true;
|
||||
} else if (start_chan_last_value <= RC_Channel::AUX_PWM_TRIGGER_LOW) {
|
||||
} else if (aux_pos == RC_Channel::AuxSwitchPos::LOW) {
|
||||
should_run = false;
|
||||
|
||||
// clear the single start flag now that we will be stopping the engine
|
||||
@ -622,15 +596,13 @@ bool AP_ICEngine::engine_control(float start_control, float cold_start, float he
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Engine: already running");
|
||||
return false;
|
||||
}
|
||||
RC_Channel *c = rc().find_channel_for_option(RC_Channel::AUX_FUNC::ICE_START_STOP);
|
||||
if (c != nullptr && rc().has_valid_input()) {
|
||||
// get starter control channel
|
||||
uint16_t cvalue = c->get_radio_in();
|
||||
if (cvalue >= start_chan_min_pwm && cvalue <= RC_Channel::AUX_PWM_TRIGGER_LOW) {
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Engine: start control disabled");
|
||||
return false;
|
||||
}
|
||||
|
||||
// get starter control channel
|
||||
if (aux_pos == RC_Channel::AuxSwitchPos::LOW) {
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Engine: start control disabled by aux function");
|
||||
return false;
|
||||
}
|
||||
|
||||
if (height_delay > 0) {
|
||||
height_pending = true;
|
||||
initial_height = 0;
|
||||
|
@ -27,6 +27,7 @@
|
||||
#include <AP_RPM/AP_RPM_config.h>
|
||||
#include <AP_HAL/I2CDevice.h>
|
||||
#include <AP_Relay/AP_Relay_config.h>
|
||||
#include <RC_Channel/RC_Channel.h>
|
||||
|
||||
#if AP_ICENGINE_TCA9554_STARTER_ENABLED
|
||||
#include "AP_ICEngine_TCA9554.h"
|
||||
@ -69,6 +70,9 @@ public:
|
||||
// do we have throttle while disarmed enabled?
|
||||
bool allow_throttle_while_disarmed(void) const;
|
||||
|
||||
// Handle incoming aux function trigger
|
||||
void do_aux_function(const RC_Channel::AuxSwitchPos ch_flag);
|
||||
|
||||
#if AP_RELAY_ENABLED
|
||||
// Needed for param conversion from relay numbers to functions
|
||||
bool get_legacy_ignition_relay_index(int8_t &num);
|
||||
@ -93,9 +97,6 @@ private:
|
||||
// enable library
|
||||
AP_Int8 enable;
|
||||
|
||||
// min pwm on start channel for engine stop
|
||||
AP_Int16 start_chan_min_pwm;
|
||||
|
||||
#if AP_RPM_ENABLED
|
||||
// which RPM instance to use
|
||||
AP_Int8 rpm_instance;
|
||||
@ -169,9 +170,8 @@ private:
|
||||
return (options & uint16_t(option)) != 0;
|
||||
}
|
||||
|
||||
// start_chan debounce
|
||||
uint16_t start_chan_last_value = 1500;
|
||||
uint32_t start_chan_last_ms;
|
||||
// Last aux function value
|
||||
RC_Channel::AuxSwitchPos aux_pos = RC_Channel::AuxSwitchPos::MIDDLE;
|
||||
|
||||
#if AP_ICENGINE_TCA9554_STARTER_ENABLED
|
||||
AP_ICEngine_TCA9554 tca9554_starter;
|
||||
|
Loading…
Reference in New Issue
Block a user