AP_ICEngine.h 2.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109
  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. control of internal combustion engines (starter, ignition and choke)
  15. */
  16. #pragma once
  17. #include <AP_HAL/AP_HAL.h>
  18. #include <AP_RPM/AP_RPM.h>
  19. class AP_ICEngine {
  20. public:
  21. // constructor
  22. AP_ICEngine(const AP_RPM &_rpm);
  23. static const struct AP_Param::GroupInfo var_info[];
  24. // update engine state. Should be called at 10Hz or more
  25. void update(void);
  26. // check for throttle override
  27. bool throttle_override(uint8_t &percent);
  28. enum ICE_State {
  29. ICE_OFF=0,
  30. ICE_START_HEIGHT_DELAY=1,
  31. ICE_START_DELAY=2,
  32. ICE_STARTING=3,
  33. ICE_RUNNING=4
  34. };
  35. // get current engine control state
  36. ICE_State get_state(void) const { return state; }
  37. // handle DO_ENGINE_CONTROL messages via MAVLink or mission
  38. bool engine_control(float start_control, float cold_start, float height_delay);
  39. static AP_ICEngine *get_singleton() { return _singleton; }
  40. private:
  41. static AP_ICEngine *_singleton;
  42. const AP_RPM &rpm;
  43. enum ICE_State state;
  44. // enable library
  45. AP_Int8 enable;
  46. // channel for pilot to command engine start, 0 for none
  47. AP_Int8 start_chan;
  48. // which RPM instance to use
  49. AP_Int8 rpm_instance;
  50. // time to run starter for (seconds)
  51. AP_Float starter_time;
  52. // delay between start attempts (seconds)
  53. AP_Float starter_delay;
  54. // pwm values
  55. AP_Int16 pwm_ignition_on;
  56. AP_Int16 pwm_ignition_off;
  57. AP_Int16 pwm_starter_on;
  58. AP_Int16 pwm_starter_off;
  59. // RPM above which engine is considered to be running
  60. AP_Int32 rpm_threshold;
  61. // time when we started the starter
  62. uint32_t starter_start_time_ms;
  63. // time when we last ran the starter
  64. uint32_t starter_last_run_ms;
  65. // throttle percentage for engine start
  66. AP_Int8 start_percent;
  67. // throttle percentage for engine idle
  68. AP_Int8 idle_percent;
  69. // height when we enter ICE_START_HEIGHT_DELAY
  70. float initial_height;
  71. // height change required to start engine
  72. float height_required;
  73. // we are waiting for valid height data
  74. bool height_pending:1;
  75. };
  76. namespace AP {
  77. AP_ICEngine *ice();
  78. };