mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_ICEngine: allow for ICE with no RPM support
This commit is contained in:
parent
6429295869
commit
383994c466
@ -61,12 +61,14 @@ const AP_Param::GroupInfo AP_ICEngine::var_info[] = {
|
|||||||
// @Range: 1 10
|
// @Range: 1 10
|
||||||
AP_GROUPINFO("START_DELAY", 3, AP_ICEngine, starter_delay, 2),
|
AP_GROUPINFO("START_DELAY", 3, AP_ICEngine, starter_delay, 2),
|
||||||
|
|
||||||
|
#if AP_RPM_ENABLED
|
||||||
// @Param: RPM_THRESH
|
// @Param: RPM_THRESH
|
||||||
// @DisplayName: RPM threshold
|
// @DisplayName: RPM threshold
|
||||||
// @Description: This is the measured RPM above which the engine is considered to be running
|
// @Description: This is the measured RPM above which the engine is considered to be running
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
// @Range: 100 100000
|
// @Range: 100 100000
|
||||||
AP_GROUPINFO("RPM_THRESH", 4, AP_ICEngine, rpm_threshold, 100),
|
AP_GROUPINFO("RPM_THRESH", 4, AP_ICEngine, rpm_threshold, 100),
|
||||||
|
#endif
|
||||||
|
|
||||||
// @Param: PWM_IGN_ON
|
// @Param: PWM_IGN_ON
|
||||||
// @DisplayName: PWM value for ignition on
|
// @DisplayName: PWM value for ignition on
|
||||||
@ -96,12 +98,14 @@ const AP_Param::GroupInfo AP_ICEngine::var_info[] = {
|
|||||||
// @Range: 1000 2000
|
// @Range: 1000 2000
|
||||||
AP_GROUPINFO("PWM_STRT_OFF", 8, AP_ICEngine, pwm_starter_off, 1000),
|
AP_GROUPINFO("PWM_STRT_OFF", 8, AP_ICEngine, pwm_starter_off, 1000),
|
||||||
|
|
||||||
|
#if AP_RPM_ENABLED
|
||||||
// @Param: RPM_CHAN
|
// @Param: RPM_CHAN
|
||||||
// @DisplayName: RPM instance channel to use
|
// @DisplayName: RPM instance channel to use
|
||||||
// @Description: This is which of the RPM instances to use for detecting the RPM of the engine
|
// @Description: This is which of the RPM instances to use for detecting the RPM of the engine
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
// @Values: 0:None,1:RPM1,2:RPM2
|
// @Values: 0:None,1:RPM1,2:RPM2
|
||||||
AP_GROUPINFO("RPM_CHAN", 9, AP_ICEngine, rpm_instance, 0),
|
AP_GROUPINFO("RPM_CHAN", 9, AP_ICEngine, rpm_instance, 0),
|
||||||
|
#endif
|
||||||
|
|
||||||
// @Param: START_PCT
|
// @Param: START_PCT
|
||||||
// @DisplayName: Throttle percentage for engine start
|
// @DisplayName: Throttle percentage for engine start
|
||||||
@ -117,6 +121,7 @@ const AP_Param::GroupInfo AP_ICEngine::var_info[] = {
|
|||||||
// @Range: 0 100
|
// @Range: 0 100
|
||||||
AP_GROUPINFO("IDLE_PCT", 11, AP_ICEngine, idle_percent, 0),
|
AP_GROUPINFO("IDLE_PCT", 11, AP_ICEngine, idle_percent, 0),
|
||||||
|
|
||||||
|
#if AP_RPM_ENABLED
|
||||||
// @Param: IDLE_RPM
|
// @Param: IDLE_RPM
|
||||||
// @DisplayName: RPM Setpoint for Idle Governor
|
// @DisplayName: RPM Setpoint for Idle Governor
|
||||||
// @Description: This configures the RPM that will be commanded by the idle governor. Set to -1 to disable
|
// @Description: This configures the RPM that will be commanded by the idle governor. Set to -1 to disable
|
||||||
@ -132,6 +137,7 @@ const AP_Param::GroupInfo AP_ICEngine::var_info[] = {
|
|||||||
// @DisplayName: Slew Rate for idle control
|
// @DisplayName: Slew Rate for idle control
|
||||||
// @Description: This configures the slewrate used to adjust the idle setpoint in percentage points per second
|
// @Description: This configures the slewrate used to adjust the idle setpoint in percentage points per second
|
||||||
AP_GROUPINFO("IDLE_SLEW", 14, AP_ICEngine, idle_slew, 1),
|
AP_GROUPINFO("IDLE_SLEW", 14, AP_ICEngine, idle_slew, 1),
|
||||||
|
#endif
|
||||||
|
|
||||||
// @Param: OPTIONS
|
// @Param: OPTIONS
|
||||||
// @DisplayName: ICE options
|
// @DisplayName: ICE options
|
||||||
@ -146,6 +152,7 @@ const AP_Param::GroupInfo AP_ICEngine::var_info[] = {
|
|||||||
// @Range: 0 1300
|
// @Range: 0 1300
|
||||||
AP_GROUPINFO("STARTCHN_MIN", 16, AP_ICEngine, start_chan_min_pwm, 0),
|
AP_GROUPINFO("STARTCHN_MIN", 16, AP_ICEngine, start_chan_min_pwm, 0),
|
||||||
|
|
||||||
|
#if AP_RPM_ENABLED
|
||||||
// @Param: REDLINE_RPM
|
// @Param: REDLINE_RPM
|
||||||
// @DisplayName: RPM of the redline limit for the engine
|
// @DisplayName: RPM of the redline limit for the engine
|
||||||
// @Description: Maximum RPM for the engine provided by the manufacturer. A value of 0 disables this feature. See ICE_OPTIONS to enable or disable the governor.
|
// @Description: Maximum RPM for the engine provided by the manufacturer. A value of 0 disables this feature. See ICE_OPTIONS to enable or disable the governor.
|
||||||
@ -153,14 +160,14 @@ const AP_Param::GroupInfo AP_ICEngine::var_info[] = {
|
|||||||
// @Range: 0 2000000
|
// @Range: 0 2000000
|
||||||
// @Units: RPM
|
// @Units: RPM
|
||||||
AP_GROUPINFO("REDLINE_RPM", 17, AP_ICEngine, redline_rpm, 0),
|
AP_GROUPINFO("REDLINE_RPM", 17, AP_ICEngine, redline_rpm, 0),
|
||||||
|
#endif
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
// constructor
|
// constructor
|
||||||
AP_ICEngine::AP_ICEngine(const AP_RPM &_rpm) :
|
AP_ICEngine::AP_ICEngine()
|
||||||
rpm(_rpm)
|
|
||||||
{
|
{
|
||||||
AP_Param::setup_object_defaults(this, var_info);
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
|
|
||||||
@ -169,8 +176,10 @@ AP_ICEngine::AP_ICEngine(const AP_RPM &_rpm) :
|
|||||||
}
|
}
|
||||||
_singleton = this;
|
_singleton = this;
|
||||||
|
|
||||||
|
#if AP_RPM_ENABLED
|
||||||
// ICEngine runs at 10Hz
|
// ICEngine runs at 10Hz
|
||||||
_rpm_filter.set_cutoff_frequency(10, 0.5f);
|
_rpm_filter.set_cutoff_frequency(10, 0.5f);
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
@ -237,8 +246,6 @@ void AP_ICEngine::update(void)
|
|||||||
should_run = false;
|
should_run = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
float rpm_value;
|
|
||||||
|
|
||||||
// switch on current state to work out new state
|
// switch on current state to work out new state
|
||||||
switch (state) {
|
switch (state) {
|
||||||
case ICE_OFF:
|
case ICE_OFF:
|
||||||
@ -286,15 +293,19 @@ void AP_ICEngine::update(void)
|
|||||||
if (!should_run) {
|
if (!should_run) {
|
||||||
state = ICE_OFF;
|
state = ICE_OFF;
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "Stopped engine");
|
gcs().send_text(MAV_SEVERITY_INFO, "Stopped engine");
|
||||||
} else if (rpm_instance > 0) {
|
}
|
||||||
|
#if AP_RPM_ENABLED
|
||||||
|
else if (rpm_instance > 0) {
|
||||||
// check RPM to see if still running
|
// check RPM to see if still running
|
||||||
if (!rpm.get_rpm(rpm_instance-1, rpm_value) ||
|
float rpm_value;
|
||||||
|
if (!AP::rpm()->get_rpm(rpm_instance-1, rpm_value) ||
|
||||||
rpm_value < rpm_threshold) {
|
rpm_value < rpm_threshold) {
|
||||||
// engine has stopped when it should be running
|
// engine has stopped when it should be running
|
||||||
state = ICE_START_DELAY;
|
state = ICE_START_DELAY;
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "Uncommanded engine stop");
|
gcs().send_text(MAV_SEVERITY_INFO, "Uncommanded engine stop");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -312,8 +323,10 @@ void AP_ICEngine::update(void)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if AP_RPM_ENABLED
|
||||||
// check against redline RPM
|
// check against redline RPM
|
||||||
if (rpm_instance > 0 && redline_rpm > 0 && rpm.get_rpm(rpm_instance-1, rpm_value)) {
|
float rpm_value;
|
||||||
|
if (rpm_instance > 0 && redline_rpm > 0 && AP::rpm()->get_rpm(rpm_instance-1, rpm_value)) {
|
||||||
// update the filtered RPM value
|
// update the filtered RPM value
|
||||||
filtered_rpm_value = _rpm_filter.apply(rpm_value);
|
filtered_rpm_value = _rpm_filter.apply(rpm_value);
|
||||||
if (!redline.flag && filtered_rpm_value > redline_rpm) {
|
if (!redline.flag && filtered_rpm_value > redline_rpm) {
|
||||||
@ -330,6 +343,7 @@ void AP_ICEngine::update(void)
|
|||||||
} else {
|
} else {
|
||||||
redline.flag = false;
|
redline.flag = false;
|
||||||
}
|
}
|
||||||
|
#endif // AP_RPM_ENABLED
|
||||||
|
|
||||||
/* now set output channels */
|
/* now set output channels */
|
||||||
switch (state) {
|
switch (state) {
|
||||||
@ -395,7 +409,8 @@ bool AP_ICEngine::throttle_override(float &percentage, const float base_throttle
|
|||||||
percentage = 0;
|
percentage = 0;
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if AP_RPM_ENABLED
|
||||||
if (redline.flag && !option_set(Options::DISABLE_REDLINE_GOVERNOR)) {
|
if (redline.flag && !option_set(Options::DISABLE_REDLINE_GOVERNOR)) {
|
||||||
// limit the throttle from increasing above what the current output is
|
// limit the throttle from increasing above what the current output is
|
||||||
if (redline.throttle_percentage < 1.0f) {
|
if (redline.throttle_percentage < 1.0f) {
|
||||||
@ -419,6 +434,7 @@ bool AP_ICEngine::throttle_override(float &percentage, const float base_throttle
|
|||||||
percentage = redline.throttle_percentage - redline.governor_integrator;
|
percentage = redline.throttle_percentage - redline.governor_integrator;
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
#endif // AP_RPM_ENABLED
|
||||||
|
|
||||||
// if THROTTLE_WHILE_DISARMED is set then we use the base_throttle, allowing the pilot to control throttle while disarmed
|
// if THROTTLE_WHILE_DISARMED is set then we use the base_throttle, allowing the pilot to control throttle while disarmed
|
||||||
if (option_set(Options::THROTTLE_WHILE_DISARMED) && !hal.util->get_soft_armed() &&
|
if (option_set(Options::THROTTLE_WHILE_DISARMED) && !hal.util->get_soft_armed() &&
|
||||||
@ -474,6 +490,7 @@ void AP_ICEngine::update_idle_governor(int8_t &min_throttle)
|
|||||||
if (!enable) {
|
if (!enable) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
#if AP_RPM_ENABLED
|
||||||
const int8_t min_throttle_base = min_throttle;
|
const int8_t min_throttle_base = min_throttle;
|
||||||
|
|
||||||
// Initialize idle point to min_throttle on the first run
|
// Initialize idle point to min_throttle on the first run
|
||||||
@ -535,6 +552,7 @@ void AP_ICEngine::update_idle_governor(int8_t &min_throttle)
|
|||||||
idle_governor_integrator = constrain_float(idle_governor_integrator, min_throttle_base, 40.0f);
|
idle_governor_integrator = constrain_float(idle_governor_integrator, min_throttle_base, 40.0f);
|
||||||
|
|
||||||
min_throttle = roundf(idle_governor_integrator);
|
min_throttle = roundf(idle_governor_integrator);
|
||||||
|
#endif // AP_RPM_ENABLED
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -24,11 +24,12 @@
|
|||||||
|
|
||||||
#include <AP_Param/AP_Param.h>
|
#include <AP_Param/AP_Param.h>
|
||||||
#include <Filter/LowPassFilter.h>
|
#include <Filter/LowPassFilter.h>
|
||||||
|
#include <AP_RPM/AP_RPM_config.h>
|
||||||
|
|
||||||
class AP_ICEngine {
|
class AP_ICEngine {
|
||||||
public:
|
public:
|
||||||
// constructor
|
// constructor
|
||||||
AP_ICEngine(const class AP_RPM &_rpm);
|
AP_ICEngine();
|
||||||
|
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
@ -65,13 +66,13 @@ public:
|
|||||||
private:
|
private:
|
||||||
static AP_ICEngine *_singleton;
|
static AP_ICEngine *_singleton;
|
||||||
|
|
||||||
const class AP_RPM &rpm;
|
|
||||||
|
|
||||||
enum ICE_State state;
|
enum ICE_State state;
|
||||||
|
|
||||||
|
#if AP_RPM_ENABLED
|
||||||
// filter for RPM value
|
// filter for RPM value
|
||||||
LowPassFilterFloat _rpm_filter;
|
LowPassFilterFloat _rpm_filter;
|
||||||
float filtered_rpm_value;
|
float filtered_rpm_value;
|
||||||
|
#endif
|
||||||
|
|
||||||
// enable library
|
// enable library
|
||||||
AP_Int8 enable;
|
AP_Int8 enable;
|
||||||
@ -82,8 +83,10 @@ private:
|
|||||||
// min pwm on start channel for engine stop
|
// min pwm on start channel for engine stop
|
||||||
AP_Int16 start_chan_min_pwm;
|
AP_Int16 start_chan_min_pwm;
|
||||||
|
|
||||||
|
#if AP_RPM_ENABLED
|
||||||
// which RPM instance to use
|
// which RPM instance to use
|
||||||
AP_Int8 rpm_instance;
|
AP_Int8 rpm_instance;
|
||||||
|
#endif
|
||||||
|
|
||||||
// time to run starter for (seconds)
|
// time to run starter for (seconds)
|
||||||
AP_Float starter_time;
|
AP_Float starter_time;
|
||||||
@ -97,8 +100,10 @@ private:
|
|||||||
AP_Int16 pwm_starter_on;
|
AP_Int16 pwm_starter_on;
|
||||||
AP_Int16 pwm_starter_off;
|
AP_Int16 pwm_starter_off;
|
||||||
|
|
||||||
|
#if AP_RPM_ENABLED
|
||||||
// RPM above which engine is considered to be running
|
// RPM above which engine is considered to be running
|
||||||
AP_Int32 rpm_threshold;
|
AP_Int32 rpm_threshold;
|
||||||
|
#endif
|
||||||
|
|
||||||
// time when we started the starter
|
// time when we started the starter
|
||||||
uint32_t starter_start_time_ms;
|
uint32_t starter_start_time_ms;
|
||||||
@ -112,6 +117,7 @@ private:
|
|||||||
// throttle percentage for engine idle
|
// throttle percentage for engine idle
|
||||||
AP_Int8 idle_percent;
|
AP_Int8 idle_percent;
|
||||||
|
|
||||||
|
#if AP_RPM_ENABLED
|
||||||
// Idle Controller RPM setpoint
|
// Idle Controller RPM setpoint
|
||||||
AP_Int16 idle_rpm;
|
AP_Int16 idle_rpm;
|
||||||
|
|
||||||
@ -120,6 +126,7 @@ private:
|
|||||||
|
|
||||||
// Idle Controller Slew Rate
|
// Idle Controller Slew Rate
|
||||||
AP_Float idle_slew;
|
AP_Float idle_slew;
|
||||||
|
#endif
|
||||||
|
|
||||||
// height when we enter ICE_START_HEIGHT_DELAY
|
// height when we enter ICE_START_HEIGHT_DELAY
|
||||||
float initial_height;
|
float initial_height;
|
||||||
@ -148,6 +155,7 @@ private:
|
|||||||
uint16_t start_chan_last_value = 1500;
|
uint16_t start_chan_last_value = 1500;
|
||||||
uint32_t start_chan_last_ms;
|
uint32_t start_chan_last_ms;
|
||||||
|
|
||||||
|
#if AP_RPM_ENABLED
|
||||||
// redline rpm
|
// redline rpm
|
||||||
AP_Int32 redline_rpm;
|
AP_Int32 redline_rpm;
|
||||||
struct {
|
struct {
|
||||||
@ -155,6 +163,7 @@ private:
|
|||||||
float governor_integrator;
|
float governor_integrator;
|
||||||
float throttle_percentage;
|
float throttle_percentage;
|
||||||
} redline;
|
} redline;
|
||||||
|
#endif
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user