APM:Libraries
SIM_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  simple internal combustion motor simulation class
17 */
18 
19 #pragma once
20 
21 #include "SIM_Aircraft.h"
22 
23 namespace SITL {
24 
25 class ICEngine {
26 public:
27  const uint8_t throttle_servo;
28  const int8_t choke_servo;
29  const int8_t ignition_servo;
30  const int8_t starter_servo;
31  const float slew_rate; // percent-per-second
32 
33  ICEngine(uint8_t _throttle, int8_t _choke, int8_t _ignition, int8_t _starter, float _slew_rate) :
34  throttle_servo(_throttle),
35  choke_servo(_choke),
36  ignition_servo(_ignition),
37  starter_servo(_starter),
38  slew_rate(_slew_rate)
39  {}
40 
41  // update motor state
42  float update(const struct Aircraft::sitl_input &input);
43 
44 private:
45  float last_output;
46  uint64_t start_time_us;
47  uint64_t last_update_us;
48  union state {
49  struct {
50  bool choke:1;
51  bool ignition:1;
52  bool starter:1;
53  };
54  uint8_t value;
55  } state, last_state;
56  bool overheat:1;
57 };
58 }
const float slew_rate
Definition: SIM_ICEngine.h:31
union SITL::ICEngine::state state
uint64_t start_time_us
Definition: SIM_ICEngine.h:46
float update(const struct Aircraft::sitl_input &input)
const uint8_t throttle_servo
Definition: SIM_ICEngine.h:27
uint64_t last_update_us
Definition: SIM_ICEngine.h:47
union SITL::ICEngine::state last_state
ICEngine(uint8_t _throttle, int8_t _choke, int8_t _ignition, int8_t _starter, float _slew_rate)
Definition: SIM_ICEngine.h:33
const int8_t ignition_servo
Definition: SIM_ICEngine.h:29
const int8_t choke_servo
Definition: SIM_ICEngine.h:28
const int8_t starter_servo
Definition: SIM_ICEngine.h:30