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