SIM_ICEngine.cpp 3.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117
  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. /*
  14. simple internal combustion engine simulator class
  15. */
  16. #include "SIM_ICEngine.h"
  17. #include <stdio.h>
  18. using namespace SITL;
  19. /*
  20. update engine state, returning power output from 0 to 1
  21. */
  22. float ICEngine::update(const struct sitl_input &input)
  23. {
  24. bool have_ignition = ignition_servo>=0;
  25. bool have_choke = choke_servo>=0;
  26. bool have_starter = starter_servo>=0;
  27. float throttle_demand = (input.servos[throttle_servo]-1000) * 0.001f;
  28. state.ignition = have_ignition?input.servos[ignition_servo]>1700:true;
  29. state.choke = have_choke?input.servos[choke_servo]>1700:false;
  30. state.starter = have_starter?input.servos[starter_servo]>1700:false;
  31. uint64_t now = AP_HAL::micros64();
  32. float dt = (now - last_update_us) * 1.0e-6f;
  33. float max_change = slew_rate * 0.01f * dt;
  34. if (!have_starter) {
  35. // always on
  36. last_output = throttle_demand;
  37. return last_output;
  38. }
  39. if (state.value != last_state.value) {
  40. printf("choke:%u starter:%u ignition:%u\n",
  41. (unsigned)state.choke,
  42. (unsigned)state.starter,
  43. (unsigned)state.ignition);
  44. }
  45. if (have_ignition && !state.ignition) {
  46. // engine is off
  47. if (!state.starter) {
  48. goto engine_off;
  49. }
  50. // give 10% when on starter alone without ignition
  51. last_update_us = now;
  52. throttle_demand = 0.1;
  53. goto output;
  54. }
  55. if (have_choke && state.choke && now - start_time_us > 1000*1000UL) {
  56. // engine is choked, only run for 1s
  57. goto engine_off;
  58. }
  59. if (last_output <= 0 && !state.starter) {
  60. // not started
  61. goto engine_off;
  62. }
  63. if (start_time_us == 0 && state.starter) {
  64. if (throttle_demand > 0.2) {
  65. printf("too much throttle to start: %.2f\n", throttle_demand);
  66. } else {
  67. // start the motor
  68. if (start_time_us == 0) {
  69. printf("Engine started\n");
  70. }
  71. start_time_us = now;
  72. }
  73. }
  74. if (start_time_us != 0 && state.starter) {
  75. uint32_t starter_time_us = (now - start_time_us);
  76. if (starter_time_us > 3000*1000UL && !overheat) {
  77. overheat = true;
  78. printf("Starter overheat\n");
  79. }
  80. } else {
  81. overheat = false;
  82. }
  83. output:
  84. if (start_time_us != 0 && throttle_demand < 0.01) {
  85. // even idling it gives some thrust
  86. throttle_demand = 0.01;
  87. }
  88. last_output = constrain_float(throttle_demand, last_output-max_change, last_output+max_change);
  89. last_output = constrain_float(last_output, 0, 1);
  90. last_update_us = now;
  91. last_state = state;
  92. return last_output;
  93. engine_off:
  94. if (start_time_us != 0) {
  95. printf("Engine stopped\n");
  96. }
  97. last_update_us = AP_HAL::micros64();
  98. start_time_us = 0;
  99. last_output = 0;
  100. last_state = state;
  101. start_time_us = 0;
  102. return 0;
  103. }