2016-07-23 04:36:42 -03:00
|
|
|
/*
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
|
|
|
|
/*
|
|
|
|
control of internal combustion engines (starter, ignition and choke)
|
|
|
|
*/
|
2019-05-20 11:57:13 -03:00
|
|
|
#pragma once
|
2016-07-23 04:36:42 -03:00
|
|
|
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include <AP_RPM/AP_RPM.h>
|
|
|
|
|
|
|
|
class AP_ICEngine {
|
|
|
|
public:
|
|
|
|
// constructor
|
2019-02-04 18:03:07 -04:00
|
|
|
AP_ICEngine(const AP_RPM &_rpm);
|
2016-07-23 04:36:42 -03:00
|
|
|
|
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
|
|
|
|
|
|
|
// update engine state. Should be called at 10Hz or more
|
|
|
|
void update(void);
|
|
|
|
|
|
|
|
// check for throttle override
|
|
|
|
bool throttle_override(uint8_t &percent);
|
|
|
|
|
|
|
|
enum ICE_State {
|
|
|
|
ICE_OFF=0,
|
|
|
|
ICE_START_HEIGHT_DELAY=1,
|
|
|
|
ICE_START_DELAY=2,
|
|
|
|
ICE_STARTING=3,
|
|
|
|
ICE_RUNNING=4
|
|
|
|
};
|
|
|
|
|
|
|
|
// get current engine control state
|
|
|
|
ICE_State get_state(void) const { return state; }
|
|
|
|
|
|
|
|
// handle DO_ENGINE_CONTROL messages via MAVLink or mission
|
|
|
|
bool engine_control(float start_control, float cold_start, float height_delay);
|
2019-11-10 07:44:06 -04:00
|
|
|
|
|
|
|
// update min throttle for idle governor
|
|
|
|
void update_idle_governor(int8_t &min_throttle);
|
|
|
|
|
2019-02-20 02:24:59 -04:00
|
|
|
static AP_ICEngine *get_singleton() { return _singleton; }
|
|
|
|
|
2016-07-23 04:36:42 -03:00
|
|
|
private:
|
2019-02-20 02:24:59 -04:00
|
|
|
static AP_ICEngine *_singleton;
|
|
|
|
|
2016-07-23 04:36:42 -03:00
|
|
|
const AP_RPM &rpm;
|
|
|
|
|
|
|
|
enum ICE_State state;
|
|
|
|
|
|
|
|
// enable library
|
|
|
|
AP_Int8 enable;
|
|
|
|
|
|
|
|
// channel for pilot to command engine start, 0 for none
|
|
|
|
AP_Int8 start_chan;
|
|
|
|
|
|
|
|
// which RPM instance to use
|
|
|
|
AP_Int8 rpm_instance;
|
|
|
|
|
|
|
|
// time to run starter for (seconds)
|
|
|
|
AP_Float starter_time;
|
|
|
|
|
|
|
|
// delay between start attempts (seconds)
|
|
|
|
AP_Float starter_delay;
|
|
|
|
|
|
|
|
// pwm values
|
|
|
|
AP_Int16 pwm_ignition_on;
|
|
|
|
AP_Int16 pwm_ignition_off;
|
|
|
|
AP_Int16 pwm_starter_on;
|
|
|
|
AP_Int16 pwm_starter_off;
|
|
|
|
|
|
|
|
// RPM above which engine is considered to be running
|
|
|
|
AP_Int32 rpm_threshold;
|
2019-11-10 07:44:06 -04:00
|
|
|
|
2016-07-23 04:36:42 -03:00
|
|
|
// time when we started the starter
|
|
|
|
uint32_t starter_start_time_ms;
|
|
|
|
|
|
|
|
// time when we last ran the starter
|
|
|
|
uint32_t starter_last_run_ms;
|
|
|
|
|
|
|
|
// throttle percentage for engine start
|
|
|
|
AP_Int8 start_percent;
|
|
|
|
|
2019-04-13 07:13:51 -03:00
|
|
|
// throttle percentage for engine idle
|
|
|
|
AP_Int8 idle_percent;
|
|
|
|
|
2019-11-10 07:44:06 -04:00
|
|
|
// Idle Controller RPM setpoint
|
|
|
|
AP_Int16 idle_rpm;
|
|
|
|
|
|
|
|
// Idle Controller RPM deadband
|
|
|
|
AP_Int16 idle_db;
|
|
|
|
|
|
|
|
// Idle Controller Slew Rate
|
|
|
|
AP_Float idle_slew;
|
|
|
|
|
2016-07-23 04:36:42 -03:00
|
|
|
// height when we enter ICE_START_HEIGHT_DELAY
|
|
|
|
float initial_height;
|
|
|
|
|
|
|
|
// height change required to start engine
|
|
|
|
float height_required;
|
|
|
|
|
|
|
|
// we are waiting for valid height data
|
|
|
|
bool height_pending:1;
|
2019-11-10 07:44:06 -04:00
|
|
|
|
|
|
|
// idle governor
|
|
|
|
float idle_governor_integrator;
|
2016-07-23 04:36:42 -03:00
|
|
|
};
|
|
|
|
|
2019-02-20 02:24:59 -04:00
|
|
|
|
|
|
|
namespace AP {
|
|
|
|
AP_ICEngine *ice();
|
|
|
|
};
|