APM:Libraries
AP_ICEngine.h
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 /*
17  control of internal combustion engines (starter, ignition and choke)
18  */
19 
20 #include <AP_HAL/AP_HAL.h>
21 #include <AP_RPM/AP_RPM.h>
22 #include <AP_AHRS/AP_AHRS.h>
23 
24 class AP_ICEngine {
25 public:
26  // constructor
27  AP_ICEngine(const AP_RPM &_rpm, const AP_AHRS &_ahrs);
28 
29  static const struct AP_Param::GroupInfo var_info[];
30 
31  // update engine state. Should be called at 10Hz or more
32  void update(void);
33 
34  // check for throttle override
35  bool throttle_override(uint8_t &percent);
36 
37  enum ICE_State {
43  };
44 
45  // get current engine control state
46  ICE_State get_state(void) const { return state; }
47 
48  // handle DO_ENGINE_CONTROL messages via MAVLink or mission
49  bool engine_control(float start_control, float cold_start, float height_delay);
50 
51 private:
52  const AP_RPM &rpm;
53  const AP_AHRS &ahrs;
54 
56 
57  // enable library
58  AP_Int8 enable;
59 
60  // channel for pilot to command engine start, 0 for none
61  AP_Int8 start_chan;
62 
63  // which RPM instance to use
64  AP_Int8 rpm_instance;
65 
66  // time to run starter for (seconds)
67  AP_Float starter_time;
68 
69  // delay between start attempts (seconds)
70  AP_Float starter_delay;
71 
72  // pwm values
73  AP_Int16 pwm_ignition_on;
74  AP_Int16 pwm_ignition_off;
75  AP_Int16 pwm_starter_on;
76  AP_Int16 pwm_starter_off;
77 
78  // RPM above which engine is considered to be running
79  AP_Int32 rpm_threshold;
80 
81  // time when we started the starter
83 
84  // time when we last ran the starter
86 
87  // throttle percentage for engine start
88  AP_Int8 start_percent;
89 
90  // height when we enter ICE_START_HEIGHT_DELAY
92 
93  // height change required to start engine
95 
96  // we are waiting for valid height data
98 };
99 
float initial_height
Definition: AP_ICEngine.h:91
AP_Float starter_delay
Definition: AP_ICEngine.h:70
const AP_AHRS & ahrs
Definition: AP_ICEngine.h:53
AP_Int16 pwm_starter_on
Definition: AP_ICEngine.h:75
bool height_pending
Definition: AP_ICEngine.h:97
bool throttle_override(uint8_t &percent)
AP_Int16 pwm_ignition_off
Definition: AP_ICEngine.h:74
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_ICEngine.h:29
AP_Int8 start_chan
Definition: AP_ICEngine.h:61
ICE_State get_state(void) const
Definition: AP_ICEngine.h:46
Definition: AP_RPM.h:27
uint32_t starter_last_run_ms
Definition: AP_ICEngine.h:85
float height_required
Definition: AP_ICEngine.h:94
AP_Int16 pwm_starter_off
Definition: AP_ICEngine.h:76
AP_Int8 enable
Definition: AP_ICEngine.h:58
AP_Float starter_time
Definition: AP_ICEngine.h:67
enum ICE_State state
Definition: AP_ICEngine.h:55
const AP_RPM & rpm
Definition: AP_ICEngine.h:52
AP_Int8 rpm_instance
Definition: AP_ICEngine.h:64
AP_Int8 start_percent
Definition: AP_ICEngine.h:88
uint32_t starter_start_time_ms
Definition: AP_ICEngine.h:82
float percent
AP_Int16 pwm_ignition_on
Definition: AP_ICEngine.h:73
void update(void)
AP_ICEngine(const AP_RPM &_rpm, const AP_AHRS &_ahrs)
AP_Int32 rpm_threshold
Definition: AP_ICEngine.h:79
bool engine_control(float start_control, float cold_start, float height_delay)