Double MSP (TLM and MAVLink) throughput for Gemini hardware (#3037)
[ExpressLRS.git] / src / lib / THERMAL / devThermal.cpp
blob42fb6617c0a3e1ec3c9c2d321448c0e1ef8c9bd1
1 #include "targets.h"
2 #include "devThermal.h"
4 #if defined(PLATFORM_ESP32)
5 #include "config.h"
6 #include "logging.h"
8 #define THERMAL_DURATION 1000
10 #include "thermal.h"
12 Thermal thermal;
14 #if defined(HAS_SMART_FAN)
15 bool is_smart_fan_control = false;
16 bool is_smart_fan_working = false;
17 #endif
19 #include "POWERMGNT.h"
21 constexpr uint8_t fanChannel = 0;
23 #define FAN_MIN_CHANGETIME 10U // intervals (seconds)
25 static uint16_t currentRPM = 0;
27 void init_rpm_counter(int pin);
28 uint32_t get_rpm();
30 static bool initialize()
32 bool enabled = false;
33 #if defined(PLATFORM_ESP32_S3)
34 thermal.init();
35 enabled = true;
36 #else
37 if (OPT_HAS_THERMAL_LM75A && GPIO_PIN_SCL != UNDEF_PIN && GPIO_PIN_SDA != UNDEF_PIN)
39 thermal.init();
40 enabled = true;
42 #endif
43 if (GPIO_PIN_FAN_EN != UNDEF_PIN)
45 pinMode(GPIO_PIN_FAN_EN, OUTPUT);
46 enabled = true;
48 return enabled;
51 static void timeoutThermal()
53 #if defined(TARGET_TX)
54 #if !defined(PLATFORM_ESP32_S3)
55 if(OPT_HAS_THERMAL_LM75A)
56 #endif
58 thermal.handle();
59 #ifdef HAS_SMART_FAN
60 if(is_smart_fan_control & !is_smart_fan_working){
61 is_smart_fan_working = true;
62 thermal.update_threshold(USER_SMARTFAN_OFF);
64 if(!is_smart_fan_control & is_smart_fan_working){
65 is_smart_fan_working = false;
66 #endif
67 thermal.update_threshold(config.GetFanMode());
68 #ifdef HAS_SMART_FAN
70 #endif
72 #endif
75 #if defined(TARGET_TX) && defined(PLATFORM_ESP32)
76 static void setFanSpeed()
78 const uint8_t defaultFanSpeeds[] = {
79 31, // 10mW
80 47, // 25mW
81 63, // 50mW
82 95, // 100mW
83 127, // 250mW
84 191, // 500mW
85 255, // 1000mW
86 255 // 2000mW
89 uint32_t speed = GPIO_PIN_FAN_SPEEDS == nullptr ? defaultFanSpeeds[POWERMGNT::currPower()] : GPIO_PIN_FAN_SPEEDS[POWERMGNT::currPower()-POWERMGNT::getMinPower()];
90 ledcWrite(fanChannel, speed);
91 DBGLN("Fan speed: %d (power) -> %u (pwm)", POWERMGNT::currPower(), speed);
93 #endif
96 * For enable-only fans:
97 * Checks the PowerFanThreshold vs CurrPower and enables the fan if at or above the threshold
98 * using a hysteresis. To turn on it must be at/above the threshold for a small time
99 * and then to turn off it must be below the threshold for FAN_MIN_RUNTIME intervals.
100 * For PWM fans:
101 * all of the above applies, but rather than just turning the fan on, the speed of the fan
102 * is set according to the power output level.
104 static void timeoutFan()
106 static uint8_t fanStateDuration;
107 static bool fanIsOn;
108 #if defined(TARGET_RX)
109 bool fanShouldBeOn = true;
110 #else
111 bool fanShouldBeOn = POWERMGNT::currPower() >= (PowerLevels_e)config.GetPowerFanThreshold();
112 #endif
113 if (fanIsOn)
115 if (fanShouldBeOn)
117 #if defined(TARGET_TX) && defined(PLATFORM_ESP32)
118 if (GPIO_PIN_FAN_PWM != UNDEF_PIN)
120 static PowerLevels_e lastPower = MinPower;
121 if (POWERMGNT::currPower() < lastPower && fanStateDuration < FAN_MIN_CHANGETIME)
123 ++fanStateDuration;
125 if (POWERMGNT::currPower() > lastPower || fanStateDuration >= FAN_MIN_CHANGETIME)
127 setFanSpeed();
128 lastPower = POWERMGNT::currPower();
129 fanStateDuration = 0; // reset the timeout
132 else
133 #endif
135 fanStateDuration = 0; // reset the timeout
138 else if (fanStateDuration < firmwareOptions.fan_min_runtime)
140 ++fanStateDuration; // counting to turn off
142 else
144 // turn off expired
145 if (GPIO_PIN_FAN_EN != UNDEF_PIN)
147 digitalWrite(GPIO_PIN_FAN_EN, LOW);
149 else if (GPIO_PIN_FAN_PWM != UNDEF_PIN)
151 ledcWrite(fanChannel, 0);
153 fanStateDuration = 0;
154 fanIsOn = false;
157 // vv else fan is off currently vv
158 else if (fanShouldBeOn)
160 // Delay turning the fan on for 4 cycles to be sure it really should be on
161 if (fanStateDuration < 3)
163 ++fanStateDuration; // counting to turn on
165 else
167 if (GPIO_PIN_FAN_EN != UNDEF_PIN)
169 digitalWrite(GPIO_PIN_FAN_EN, HIGH);
170 fanStateDuration = 0;
172 else if (GPIO_PIN_FAN_PWM != UNDEF_PIN)
174 // bump the fan to full power for one cycle in case
175 // the PWM level is not sufficient to get it moving
176 ledcWrite(fanChannel, 192);
177 fanStateDuration = FAN_MIN_CHANGETIME;
179 fanIsOn = true;
184 uint16_t getCurrentRPM()
186 return currentRPM;
189 #if !defined(PLATFORM_ESP32_C3)
190 static void timeoutTacho()
192 if (GPIO_PIN_FAN_TACHO != UNDEF_PIN)
194 currentRPM = get_rpm();
195 DBGVLN("RPM %d", currentRPM);
198 #endif
200 static int start()
202 if (GPIO_PIN_FAN_PWM != UNDEF_PIN)
204 ledcSetup(fanChannel, 25000, 8);
205 ledcAttachPin(GPIO_PIN_FAN_PWM, fanChannel);
206 ledcWrite(fanChannel, 0);
208 #if !defined(PLATFORM_ESP32_C3)
209 if (GPIO_PIN_FAN_TACHO != UNDEF_PIN)
211 init_rpm_counter(GPIO_PIN_FAN_TACHO);
213 #endif
214 return DURATION_IMMEDIATELY;
217 static int event()
219 #if defined(TARGET_TX)
220 if (OPT_HAS_THERMAL_LM75A && GPIO_PIN_SCL != UNDEF_PIN && GPIO_PIN_SDA != UNDEF_PIN)
222 #ifdef HAS_SMART_FAN
223 if(!is_smart_fan_control)
225 #endif
226 thermal.update_threshold(config.GetFanMode());
227 #ifdef HAS_SMART_FAN
229 #endif
231 #endif
232 return DURATION_IGNORE;
235 static int timeout()
237 timeoutThermal();
238 timeoutFan();
239 #if !defined(PLATFORM_ESP32_C3)
240 timeoutTacho();
241 #endif
242 return THERMAL_DURATION;
245 device_t Thermal_device = {
246 .initialize = initialize,
247 .start = start,
248 .event = event,
249 .timeout = timeout
251 #endif