6 #if defined(Regulatory_Domain_AU_915) || defined(Regulatory_Domain_EU_868) || defined(Regulatory_Domain_IN_866) || defined(Regulatory_Domain_FCC_915) || defined(Regulatory_Domain_AU_433) || defined(Regulatory_Domain_EU_433)
7 #include "SX127xDriver.h"
8 #elif Regulatory_Domain_ISM_2400
9 #include "SX1280Driver.h"
12 #if defined(PLATFORM_ESP32)
13 #include <nvs_flash.h>
17 #if defined(TARGET_RX)
18 // These are "fake" values as the power on the RX is not user selectable
19 #define MinPower PWR_10mW
20 #define MaxPower PWR_10mW
23 #if defined(HighPower) && !defined(UNLOCK_HIGHER_POWER)
25 #define MaxPower HighPower
28 #if !defined(DefaultPower)
29 #define DefaultPower PWR_50mW
49 static PowerLevels_e CurrentPower
;
50 static PowerLevels_e FanEnableThreshold
;
51 static void updateFan();
52 #if defined(PLATFORM_ESP32)
53 static nvs_handle handle
;
55 static void LoadCalibration();
58 static void setPower(PowerLevels_e Power
);
59 static PowerLevels_e
incPower();
60 static PowerLevels_e
decPower();
61 static PowerLevels_e
currPower();
62 static uint8_t powerToCrsfPower(PowerLevels_e Power
);
63 static PowerLevels_e
getDefaultPower();
64 static void setDefaultPower();
65 static void setFanEnableTheshold(PowerLevels_e Power
);
67 static void SetPowerCaliValues(int8_t *values
, size_t size
);
68 static void GetPowerCaliValues(int8_t *values
, size_t size
);
72 #define CALIBRATION_MAGIC 0x43414C << 8 //['C', 'A', 'L']
73 #define CALIBRATION_VERSION 1