APM:Libraries
AP_ICEngine.cpp
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 
18 #include <GCS_MAVLink/GCS.h>
19 #include "AP_ICEngine.h"
20 
21 extern const AP_HAL::HAL& hal;
22 
24 
25  // @Param: ENABLE
26  // @DisplayName: Enable ICEngine control
27  // @Description: This enables internal combusion engine control
28  // @Values: 0:Disabled, 1:Enabled
29  // @User: Advanced
30  AP_GROUPINFO_FLAGS("ENABLE", 0, AP_ICEngine, enable, 0, AP_PARAM_FLAG_ENABLE),
31 
32  // @Param: START_CHAN
33  // @DisplayName: Input channel for engine start
34  // @Description: This is an RC input channel for requesting engine start. Engine will try to start when channel is at or above 1700. Engine will stop when channel is at or below 1300. Between 1301 and 1699 the engine will not change state unless a MAVLink command or mission item commands a state change, or the vehicle is disamed.
35  // @User: Standard
36  // @Values: 0:None,1:Chan1,2:Chan2,3:Chan3,4:Chan4,5:Chan5,6:Chan6,7:Chan7,8:Chan8,9:Chan9,10:Chan10,11:Chan11,12:Chan12,13:Chan13,14:Chan14,15:Chan15,16:Chan16
37  AP_GROUPINFO("START_CHAN", 1, AP_ICEngine, start_chan, 0),
38 
39  // @Param: STARTER_TIME
40  // @DisplayName: Time to run starter
41  // @Description: This is the number of seconds to run the starter when trying to start the engine
42  // @User: Standard
43  // @Units: s
44  // @Range: 0.1 5
45  AP_GROUPINFO("STARTER_TIME", 2, AP_ICEngine, starter_time, 3),
46 
47  // @Param: START_DELAY
48  // @DisplayName: Time to wait between starts
49  // @Description: Delay between start attempts
50  // @User: Standard
51  // @Units: s
52  // @Range: 1 10
53  AP_GROUPINFO("START_DELAY", 3, AP_ICEngine, starter_delay, 2),
54 
55  // @Param: RPM_THRESH
56  // @DisplayName: RPM threshold
57  // @Description: This is the measured RPM above which tne engine is considered to be running
58  // @User: Standard
59  // @Range: 100 100000
60  AP_GROUPINFO("RPM_THRESH", 4, AP_ICEngine, rpm_threshold, 100),
61 
62  // @Param: PWM_IGN_ON
63  // @DisplayName: PWM value for ignition on
64  // @Description: This is the value sent to the ignition channel when on
65  // @User: Standard
66  // @Range: 1000 2000
67  AP_GROUPINFO("PWM_IGN_ON", 5, AP_ICEngine, pwm_ignition_on, 2000),
68 
69  // @Param: PWM_IGN_OFF
70  // @DisplayName: PWM value for ignition off
71  // @Description: This is the value sent to the ignition channel when off
72  // @User: Standard
73  // @Range: 1000 2000
74  AP_GROUPINFO("PWM_IGN_OFF", 6, AP_ICEngine, pwm_ignition_off, 1000),
75 
76  // @Param: PWM_STRT_ON
77  // @DisplayName: PWM value for starter on
78  // @Description: This is the value sent to the starter channel when on
79  // @User: Standard
80  // @Range: 1000 2000
81  AP_GROUPINFO("PWM_STRT_ON", 7, AP_ICEngine, pwm_starter_on, 2000),
82 
83  // @Param: PWM_STRT_OFF
84  // @DisplayName: PWM value for starter off
85  // @Description: This is the value sent to the starter channel when off
86  // @User: Standard
87  // @Range: 1000 2000
88  AP_GROUPINFO("PWM_STRT_OFF", 8, AP_ICEngine, pwm_starter_off, 1000),
89 
90  // @Param: RPM_CHAN
91  // @DisplayName: RPM instance channel to use
92  // @Description: This is which of the RPM instances to use for detecting the RPM of the engine
93  // @User: Standard
94  // @Values: 0:None,1:RPM1,2:RPM2
95  AP_GROUPINFO("RPM_CHAN", 9, AP_ICEngine, rpm_instance, 0),
96 
97  // @Param: START_PCT
98  // @DisplayName: Throttle percentage for engine start
99  // @Description: This is the percentage throttle output for engine start
100  // @User: Standard
101  // @Range: 0 100
102  AP_GROUPINFO("START_PCT", 10, AP_ICEngine, start_percent, 5),
103 
104  AP_GROUPEND
105 };
106 
107 
108 // constructor
109 AP_ICEngine::AP_ICEngine(const AP_RPM &_rpm, const AP_AHRS &_ahrs) :
110  rpm(_rpm),
111  ahrs(_ahrs),
112  state(ICE_OFF)
113 {
115 }
116 
117 /*
118  update engine state
119  */
121 {
122  if (!enable) {
123  return;
124  }
125 
126  uint16_t cvalue = 1500;
127  if (start_chan != 0) {
128  // get starter control channel
130  }
131 
132  bool should_run = false;
133  uint32_t now = AP_HAL::millis();
134 
135  if (state == ICE_OFF && cvalue >= 1700) {
136  should_run = true;
137  } else if (cvalue <= 1300) {
138  should_run = false;
139  } else if (state != ICE_OFF) {
140  should_run = true;
141  }
142 
143  // switch on current state to work out new state
144  switch (state) {
145  case ICE_OFF:
146  if (should_run) {
148  }
149  break;
150 
151  case ICE_START_HEIGHT_DELAY: {
152  Vector3f pos;
153  if (!should_run) {
154  state = ICE_OFF;
155  } else if (ahrs.get_relative_position_NED_origin(pos)) {
156  if (height_pending) {
157  height_pending = false;
158  initial_height = -pos.z;
159  } else if ((-pos.z) >= initial_height + height_required) {
160  gcs().send_text(MAV_SEVERITY_INFO, "Starting height reached %.1f",
161  (double)(-pos.z - initial_height));
163  }
164  }
165  break;
166  }
167 
168  case ICE_START_DELAY:
169  if (!should_run) {
170  state = ICE_OFF;
171  } else if (now - starter_last_run_ms >= starter_delay*1000) {
172  gcs().send_text(MAV_SEVERITY_INFO, "Starting engine");
174  }
175  break;
176 
177  case ICE_STARTING:
178  if (!should_run) {
179  state = ICE_OFF;
180  } else if (now - starter_start_time_ms >= starter_time*1000) {
181  state = ICE_RUNNING;
182  }
183  break;
184 
185  case ICE_RUNNING:
186  if (!should_run) {
187  state = ICE_OFF;
188  gcs().send_text(MAV_SEVERITY_INFO, "Stopped engine");
189  } else if (rpm_instance > 0) {
190  // check RPM to see if still running
191  if (!rpm.healthy(rpm_instance-1) ||
193  // engine has stopped when it should be running
195  }
196  }
197  break;
198  }
199 
200  if (!hal.util->get_soft_armed()) {
201  if (state == ICE_START_HEIGHT_DELAY) {
202  // when disarmed we can be waiting for takeoff
203  Vector3f pos;
205  // reset initial height while disarmed
206  initial_height = -pos.z;
207  }
208  } else {
209  // force ignition off when disarmed
210  state = ICE_OFF;
211  }
212  }
213 
214  /* now set output channels */
215  switch (state) {
216  case ICE_OFF:
220  break;
221 
223  case ICE_START_DELAY:
226  break;
227 
228  case ICE_STARTING:
231  if (starter_start_time_ms == 0) {
232  starter_start_time_ms = now;
233  }
234  starter_last_run_ms = now;
235  break;
236 
237  case ICE_RUNNING:
241  break;
242  }
243 }
244 
245 
246 /*
247  check for throttle override. This allows the ICE controller to force
248  the correct starting throttle when starting the engine
249  */
250 bool AP_ICEngine::throttle_override(uint8_t &percentage)
251 {
252  if (!enable) {
253  return false;
254  }
255  if (state == ICE_STARTING || state == ICE_START_DELAY) {
256  percentage = (uint8_t)start_percent.get();
257  return true;
258  }
259  return false;
260 }
261 
262 
263 /*
264  handle DO_ENGINE_CONTROL messages via MAVLink or mission
265 */
266 bool AP_ICEngine::engine_control(float start_control, float cold_start, float height_delay)
267 {
268  if (start_control <= 0) {
269  state = ICE_OFF;
270  return true;
271  }
272  if (start_chan != 0) {
273  // get starter control channel
274  if (RC_Channels::get_radio_in(start_chan-1) <= 1300) {
275  gcs().send_text(MAV_SEVERITY_INFO, "Engine: start control disabled");
276  return false;
277  }
278  }
279  if (height_delay > 0) {
280  height_pending = true;
281  initial_height = 0;
282  height_required = height_delay;
284  gcs().send_text(MAV_SEVERITY_INFO, "Takeoff height set to %.1fm", (double)height_delay);
285  return true;
286  }
288  return true;
289 }
float initial_height
Definition: AP_ICEngine.h:91
bool get_soft_armed() const
Definition: Util.h:15
#define AP_PARAM_FLAG_ENABLE
Definition: AP_Param.h:56
AP_Float starter_delay
Definition: AP_ICEngine.h:70
float get_rpm(uint8_t instance) const
Definition: AP_RPM.h:77
const AP_AHRS & ahrs
Definition: AP_ICEngine.h:53
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
AP_Int16 pwm_starter_on
Definition: AP_ICEngine.h:75
Interface definition for the various Ground Control System.
bool height_pending
Definition: AP_ICEngine.h:97
bool throttle_override(uint8_t &percent)
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
virtual bool get_relative_position_NED_origin(Vector3f &vec) const
Definition: AP_AHRS.h:333
AP_Int16 pwm_ignition_off
Definition: AP_ICEngine.h:74
AP_HAL::Util * util
Definition: HAL.h:115
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
GCS & gcs()
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_ICEngine.h:29
#define AP_GROUPINFO_FLAGS(name, idx, clazz, element, def, flags)
Definition: AP_Param.h:93
AP_Int8 start_chan
Definition: AP_ICEngine.h:61
bool healthy(uint8_t instance) const
Definition: AP_RPM.cpp:164
static void set_output_pwm(SRV_Channel::Aux_servo_function_t function, uint16_t value)
uint32_t millis()
Definition: system.cpp:157
Definition: AP_RPM.h:27
T z
Definition: vector3.h:67
uint32_t starter_last_run_ms
Definition: AP_ICEngine.h:85
static int state
Definition: Util.cpp:20
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Definition: GCS.cpp:8
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
static uint16_t get_radio_in(const uint8_t chan)
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
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
#define AP_GROUPEND
Definition: AP_Param.h:121
bool engine_control(float start_control, float cold_start, float height_delay)
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214