AP_ICEngine.cpp 10 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320
  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. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. #include <SRV_Channel/SRV_Channel.h>
  14. #include <GCS_MAVLink/GCS.h>
  15. #include <AP_AHRS/AP_AHRS.h>
  16. #include "AP_ICEngine.h"
  17. extern const AP_HAL::HAL& hal;
  18. const AP_Param::GroupInfo AP_ICEngine::var_info[] = {
  19. // @Param: ENABLE
  20. // @DisplayName: Enable ICEngine control
  21. // @Description: This enables internal combustion engine control
  22. // @Values: 0:Disabled, 1:Enabled
  23. // @User: Advanced
  24. AP_GROUPINFO_FLAGS("ENABLE", 0, AP_ICEngine, enable, 0, AP_PARAM_FLAG_ENABLE),
  25. // @Param: START_CHAN
  26. // @DisplayName: Input channel for engine start
  27. // @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.
  28. // @User: Standard
  29. // @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
  30. AP_GROUPINFO("START_CHAN", 1, AP_ICEngine, start_chan, 0),
  31. // @Param: STARTER_TIME
  32. // @DisplayName: Time to run starter
  33. // @Description: This is the number of seconds to run the starter when trying to start the engine
  34. // @User: Standard
  35. // @Units: s
  36. // @Range: 0.1 5
  37. AP_GROUPINFO("STARTER_TIME", 2, AP_ICEngine, starter_time, 3),
  38. // @Param: START_DELAY
  39. // @DisplayName: Time to wait between starts
  40. // @Description: Delay between start attempts
  41. // @User: Standard
  42. // @Units: s
  43. // @Range: 1 10
  44. AP_GROUPINFO("START_DELAY", 3, AP_ICEngine, starter_delay, 2),
  45. // @Param: RPM_THRESH
  46. // @DisplayName: RPM threshold
  47. // @Description: This is the measured RPM above which the engine is considered to be running
  48. // @User: Standard
  49. // @Range: 100 100000
  50. AP_GROUPINFO("RPM_THRESH", 4, AP_ICEngine, rpm_threshold, 100),
  51. // @Param: PWM_IGN_ON
  52. // @DisplayName: PWM value for ignition on
  53. // @Description: This is the value sent to the ignition channel when on
  54. // @User: Standard
  55. // @Range: 1000 2000
  56. AP_GROUPINFO("PWM_IGN_ON", 5, AP_ICEngine, pwm_ignition_on, 2000),
  57. // @Param: PWM_IGN_OFF
  58. // @DisplayName: PWM value for ignition off
  59. // @Description: This is the value sent to the ignition channel when off
  60. // @User: Standard
  61. // @Range: 1000 2000
  62. AP_GROUPINFO("PWM_IGN_OFF", 6, AP_ICEngine, pwm_ignition_off, 1000),
  63. // @Param: PWM_STRT_ON
  64. // @DisplayName: PWM value for starter on
  65. // @Description: This is the value sent to the starter channel when on
  66. // @User: Standard
  67. // @Range: 1000 2000
  68. AP_GROUPINFO("PWM_STRT_ON", 7, AP_ICEngine, pwm_starter_on, 2000),
  69. // @Param: PWM_STRT_OFF
  70. // @DisplayName: PWM value for starter off
  71. // @Description: This is the value sent to the starter channel when off
  72. // @User: Standard
  73. // @Range: 1000 2000
  74. AP_GROUPINFO("PWM_STRT_OFF", 8, AP_ICEngine, pwm_starter_off, 1000),
  75. // @Param: RPM_CHAN
  76. // @DisplayName: RPM instance channel to use
  77. // @Description: This is which of the RPM instances to use for detecting the RPM of the engine
  78. // @User: Standard
  79. // @Values: 0:None,1:RPM1,2:RPM2
  80. AP_GROUPINFO("RPM_CHAN", 9, AP_ICEngine, rpm_instance, 0),
  81. // @Param: START_PCT
  82. // @DisplayName: Throttle percentage for engine start
  83. // @Description: This is the percentage throttle output for engine start
  84. // @User: Standard
  85. // @Range: 0 100
  86. AP_GROUPINFO("START_PCT", 10, AP_ICEngine, start_percent, 5),
  87. // @Param: IDLE_PCT
  88. // @DisplayName: Throttle percentage for engine idle
  89. // @Description: This is the minimum percentage throttle output while running, this includes being disarmed, but not safe
  90. // @User: Standard
  91. // @Range: 0 100
  92. AP_GROUPINFO("IDLE_PCT", 11, AP_ICEngine, idle_percent, 0),
  93. AP_GROUPEND
  94. };
  95. // constructor
  96. AP_ICEngine::AP_ICEngine(const AP_RPM &_rpm) :
  97. rpm(_rpm)
  98. {
  99. AP_Param::setup_object_defaults(this, var_info);
  100. if (_singleton != nullptr) {
  101. AP_HAL::panic("AP_ICEngine must be singleton");
  102. }
  103. _singleton = this;
  104. }
  105. /*
  106. update engine state
  107. */
  108. void AP_ICEngine::update(void)
  109. {
  110. if (!enable) {
  111. return;
  112. }
  113. uint16_t cvalue = 1500;
  114. RC_Channel *c = rc().channel(start_chan-1);
  115. if (c != nullptr) {
  116. // get starter control channel
  117. cvalue = c->get_radio_in();
  118. }
  119. bool should_run = false;
  120. uint32_t now = AP_HAL::millis();
  121. if (state == ICE_OFF && cvalue >= 1700) {
  122. should_run = true;
  123. } else if (cvalue <= 1300) {
  124. should_run = false;
  125. } else if (state != ICE_OFF) {
  126. should_run = true;
  127. }
  128. // switch on current state to work out new state
  129. switch (state) {
  130. case ICE_OFF:
  131. if (should_run) {
  132. state = ICE_START_DELAY;
  133. }
  134. break;
  135. case ICE_START_HEIGHT_DELAY: {
  136. Vector3f pos;
  137. if (!should_run) {
  138. state = ICE_OFF;
  139. } else if (AP::ahrs().get_relative_position_NED_origin(pos)) {
  140. if (height_pending) {
  141. height_pending = false;
  142. initial_height = -pos.z;
  143. } else if ((-pos.z) >= initial_height + height_required) {
  144. gcs().send_text(MAV_SEVERITY_INFO, "Starting height reached %.1f",
  145. (double)(-pos.z - initial_height));
  146. state = ICE_STARTING;
  147. }
  148. }
  149. break;
  150. }
  151. case ICE_START_DELAY:
  152. if (!should_run) {
  153. state = ICE_OFF;
  154. } else if (now - starter_last_run_ms >= starter_delay*1000) {
  155. gcs().send_text(MAV_SEVERITY_INFO, "Starting engine");
  156. state = ICE_STARTING;
  157. }
  158. break;
  159. case ICE_STARTING:
  160. if (!should_run) {
  161. state = ICE_OFF;
  162. } else if (now - starter_start_time_ms >= starter_time*1000) {
  163. state = ICE_RUNNING;
  164. }
  165. break;
  166. case ICE_RUNNING:
  167. if (!should_run) {
  168. state = ICE_OFF;
  169. gcs().send_text(MAV_SEVERITY_INFO, "Stopped engine");
  170. } else if (rpm_instance > 0) {
  171. // check RPM to see if still running
  172. if (!rpm.healthy(rpm_instance-1) ||
  173. rpm.get_rpm(rpm_instance-1) < rpm_threshold) {
  174. // engine has stopped when it should be running
  175. state = ICE_START_DELAY;
  176. }
  177. }
  178. break;
  179. }
  180. if (!hal.util->get_soft_armed()) {
  181. if (state == ICE_START_HEIGHT_DELAY) {
  182. // when disarmed we can be waiting for takeoff
  183. Vector3f pos;
  184. if (AP::ahrs().get_relative_position_NED_origin(pos)) {
  185. // reset initial height while disarmed
  186. initial_height = -pos.z;
  187. }
  188. } else if (idle_percent <= 0) { // check if we should idle
  189. // force ignition off when disarmed
  190. state = ICE_OFF;
  191. }
  192. }
  193. /* now set output channels */
  194. switch (state) {
  195. case ICE_OFF:
  196. SRV_Channels::set_output_pwm(SRV_Channel::k_ignition, pwm_ignition_off);
  197. SRV_Channels::set_output_pwm(SRV_Channel::k_starter, pwm_starter_off);
  198. starter_start_time_ms = 0;
  199. break;
  200. case ICE_START_HEIGHT_DELAY:
  201. case ICE_START_DELAY:
  202. SRV_Channels::set_output_pwm(SRV_Channel::k_ignition, pwm_ignition_on);
  203. SRV_Channels::set_output_pwm(SRV_Channel::k_starter, pwm_starter_off);
  204. break;
  205. case ICE_STARTING:
  206. SRV_Channels::set_output_pwm(SRV_Channel::k_ignition, pwm_ignition_on);
  207. SRV_Channels::set_output_pwm(SRV_Channel::k_starter, pwm_starter_on);
  208. if (starter_start_time_ms == 0) {
  209. starter_start_time_ms = now;
  210. }
  211. starter_last_run_ms = now;
  212. break;
  213. case ICE_RUNNING:
  214. SRV_Channels::set_output_pwm(SRV_Channel::k_ignition, pwm_ignition_on);
  215. SRV_Channels::set_output_pwm(SRV_Channel::k_starter, pwm_starter_off);
  216. starter_start_time_ms = 0;
  217. break;
  218. }
  219. }
  220. /*
  221. check for throttle override. This allows the ICE controller to force
  222. the correct starting throttle when starting the engine and maintain idle when disarmed
  223. */
  224. bool AP_ICEngine::throttle_override(uint8_t &percentage)
  225. {
  226. if (!enable) {
  227. return false;
  228. }
  229. if (state == ICE_RUNNING &&
  230. idle_percent > 0 &&
  231. idle_percent < 100 &&
  232. (int16_t)idle_percent > SRV_Channels::get_output_scaled(SRV_Channel::k_throttle))
  233. {
  234. percentage = (uint8_t)idle_percent;
  235. return true;
  236. }
  237. if (state == ICE_STARTING || state == ICE_START_DELAY) {
  238. percentage = (uint8_t)start_percent.get();
  239. return true;
  240. }
  241. return false;
  242. }
  243. /*
  244. handle DO_ENGINE_CONTROL messages via MAVLink or mission
  245. */
  246. bool AP_ICEngine::engine_control(float start_control, float cold_start, float height_delay)
  247. {
  248. if (start_control <= 0) {
  249. state = ICE_OFF;
  250. return true;
  251. }
  252. RC_Channel *c = rc().channel(start_chan-1);
  253. if (c != nullptr) {
  254. // get starter control channel
  255. if (c->get_radio_in() <= 1300) {
  256. gcs().send_text(MAV_SEVERITY_INFO, "Engine: start control disabled");
  257. return false;
  258. }
  259. }
  260. if (height_delay > 0) {
  261. height_pending = true;
  262. initial_height = 0;
  263. height_required = height_delay;
  264. state = ICE_START_HEIGHT_DELAY;
  265. gcs().send_text(MAV_SEVERITY_INFO, "Takeoff height set to %.1fm", (double)height_delay);
  266. return true;
  267. }
  268. state = ICE_STARTING;
  269. return true;
  270. }
  271. // singleton instance. Should only ever be set in the constructor.
  272. AP_ICEngine *AP_ICEngine::_singleton;
  273. namespace AP {
  274. AP_ICEngine *ice() {
  275. return AP_ICEngine::get_singleton();
  276. }
  277. }