makes GPIO_PIN_RST optional for the sx1276
[ExpressLRS.git] / src / lib / POWERMGNT / POWERMGNT.cpp
bloba30f1dd0b2449a8dc19ee7212a235bde784922ff
1 #include "POWERMGNT.h"
2 #include "DAC.h"
4 /*
5 * Moves the power management values and special cases out of the main code and into `targets.h`.
7 * TX Targets
8 * ***********
10 * A new target now just needs to define
11 * - `MinPower`, the minimum power level supported
12 * - `MaxPower`, the absolute maximum power level supported
13 * - optionally `HighPower`, if defined then module uses this as max unless `UNLOCK_HIGHER_POWER` is defined by the user
14 * - `POWER_OUTPUT_VALUES` array of values to be used to set appropriate power level from `MinPower` to `MaxPower`
16 * A target can also define one of the following to configure how the output power is set, the value given to the function
17 * is the value from the `POWER_OUTPUT_VALUES` array.
19 * - `POWER_OUTPUT_DAC` to use i2c DAC specify the address of the DAC in this define
20 * - `POWER_OUTPUT_DACWRITE` to use `dacWrite` function
21 * - `POWER_OUTPUT_ANALOG` to use `analogWrite` function
22 * - `POWER_OUTPUT_FIXED` which will provide the value to `Radio.SetOutputPower` function
23 * - default is to use `Radio.SetOutputPower` function
25 * RX Targets
26 * **********
28 * Can define `POWER_OUTPUT_FIXED` which will provide the value to `Radio.SetOutputPower` function.
29 * If nothing is defined then the default method `Radio.SetOutputPowerMax` will be used, which sets the value to
30 * 13 on SX1280 (~12.5dBm) or 15 on SX127x (~17dBm)
33 #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)
34 extern SX127xDriver Radio;
35 #elif Regulatory_Domain_ISM_2400
36 extern SX1280Driver Radio;
37 #endif
39 PowerLevels_e POWERMGNT::CurrentPower = PWR_COUNT; // default "undefined" initial value
40 PowerLevels_e POWERMGNT::FanEnableThreshold = PWR_250mW;
41 #if defined(POWER_OUTPUT_VALUES)
42 static int16_t powerValues[] = POWER_OUTPUT_VALUES;
43 #endif
45 static int8_t powerCaliValues[PWR_COUNT] = {0};
47 #if defined(PLATFORM_ESP32)
48 nvs_handle POWERMGNT::handle = 0;
49 #endif
51 PowerLevels_e POWERMGNT::incPower()
53 if (CurrentPower < MaxPower)
55 setPower((PowerLevels_e)((uint8_t)CurrentPower + 1));
57 return CurrentPower;
60 PowerLevels_e POWERMGNT::decPower()
62 if (CurrentPower > MinPower)
64 setPower((PowerLevels_e)((uint8_t)CurrentPower - 1));
66 return CurrentPower;
69 PowerLevels_e POWERMGNT::currPower()
71 return CurrentPower;
74 uint8_t POWERMGNT::powerToCrsfPower(PowerLevels_e Power)
76 // Crossfire's power levels as defined in opentx:radio/src/telemetry/crossfire.cpp
77 //static const int32_t power_values[] = { 0, 10, 25, 100, 500, 1000, 2000, 250, 50 };
78 switch (Power)
80 case PWR_10mW: return 1;
81 case PWR_25mW: return 2;
82 case PWR_50mW: return 8;
83 case PWR_100mW: return 3;
84 case PWR_250mW: return 7;
85 case PWR_500mW: return 4;
86 case PWR_1000mW: return 5;
87 case PWR_2000mW: return 6;
88 default:
89 return 0;
93 void POWERMGNT::SetPowerCaliValues(int8_t *values, size_t size)
95 bool isUpdate = false;
96 for(size_t i=0 ; i<size ; i++)
98 if(powerCaliValues[i] != values[i])
100 powerCaliValues[i] = values[i];
101 isUpdate = true;
104 #if defined(PLATFORM_ESP32)
105 if (isUpdate)
107 nvs_set_blob(handle, "powercali", &powerCaliValues, sizeof(powerCaliValues));
109 nvs_commit(handle);
110 #endif
113 void POWERMGNT::GetPowerCaliValues(int8_t *values, size_t size)
115 for(size_t i=0 ; i<size ; i++)
117 *(values + i) = powerCaliValues[i];
121 void POWERMGNT::LoadCalibration()
123 #if defined(PLATFORM_ESP32)
124 // Initialize NVS
125 esp_err_t err = nvs_flash_init();
126 if (err == ESP_ERR_NVS_NO_FREE_PAGES || err == ESP_ERR_NVS_NEW_VERSION_FOUND)
128 ESP_ERROR_CHECK(nvs_flash_erase());
129 err = nvs_flash_init();
131 ESP_ERROR_CHECK( err );
132 ESP_ERROR_CHECK(nvs_open("PWRCALI", NVS_READWRITE, &handle));
134 uint32_t version;
135 if(nvs_get_u32(handle, "calversion", &version) != ESP_ERR_NVS_NOT_FOUND
136 && version == (uint32_t)(CALIBRATION_VERSION | CALIBRATION_MAGIC))
138 size_t size = sizeof(powerCaliValues);
139 nvs_get_blob(handle, "powercali", &powerCaliValues, &size);
141 else
143 nvs_set_blob(handle, "powercali", &powerCaliValues, sizeof(powerCaliValues));
144 nvs_set_u32(handle, "calversion", CALIBRATION_VERSION | CALIBRATION_MAGIC);
145 nvs_commit(handle);
147 #else
148 memset(powerCaliValues, 0, sizeof(powerCaliValues));
149 #endif
153 void POWERMGNT::init()
155 #if defined(POWER_OUTPUT_DAC)
156 TxDAC.init();
157 #elif defined(POWER_OUTPUT_ANALOG)
158 //initialize both 12 bit DACs
159 pinMode(GPIO_PIN_RFamp_APC1, OUTPUT);
160 pinMode(GPIO_PIN_RFamp_APC2, OUTPUT);
161 analogWriteResolution(12);
163 // WARNING: The two calls to analogWrite below are needed for the
164 // lite pro, as it seems that the very first calls to analogWrite
165 // fail for an unknown reason (suspect Arduino lib bug). These
166 // set power to 50mW, which should get overwitten shortly after
167 // boot by whatever is set in the EEPROM. @wvarty
168 analogWrite(GPIO_PIN_RFamp_APC1, 3350); //0-4095 2.7V
169 analogWrite(GPIO_PIN_RFamp_APC2, 950);
170 #endif
171 #if defined(GPIO_PIN_FAN_EN)
172 pinMode(GPIO_PIN_FAN_EN, OUTPUT);
173 #endif
174 LoadCalibration();
175 setDefaultPower();
178 PowerLevels_e POWERMGNT::getDefaultPower()
180 if (MinPower > DefaultPower)
182 return MinPower;
184 if (MaxPower < DefaultPower)
186 return MaxPower;
188 return DefaultPower;
191 void POWERMGNT::setDefaultPower()
193 setPower(getDefaultPower());
196 void POWERMGNT::updateFan()
198 #if defined(GPIO_PIN_FAN_EN)
199 digitalWrite(GPIO_PIN_FAN_EN, (CurrentPower >= FanEnableThreshold) ? HIGH : LOW);
200 #endif
203 void POWERMGNT::setFanEnableTheshold(PowerLevels_e Power)
205 #if defined(GPIO_PIN_FAN_EN)
206 FanEnableThreshold = Power;
207 updateFan();
208 #endif
211 void POWERMGNT::setPower(PowerLevels_e Power)
213 if (Power == CurrentPower)
214 return;
216 if (Power < MinPower)
218 Power = MinPower;
220 else if (Power > MaxPower)
222 Power = MaxPower;
225 #if defined(POWER_OUTPUT_DAC)
226 // DAC is used e.g. for R9M, ES915TX and Voyager
227 Radio.SetOutputPower(0b0000);
228 TxDAC.setPower(powerValues[Power - MinPower]);
229 #elif defined(POWER_OUTPUT_ANALOG)
230 Radio.SetOutputPower(0b0000);
231 //Set DACs PA5 & PA4
232 analogWrite(GPIO_PIN_RFamp_APC1, 3350); //0-4095 2.7V
233 analogWrite(GPIO_PIN_RFamp_APC2, powerValues[Power - MinPower]);
234 #elif defined(POWER_OUTPUT_DACWRITE)
235 Radio.SetOutputPower(0b0000);
236 dacWrite(GPIO_PIN_RFamp_APC2, powerValues[Power - MinPower]);
237 #elif defined(POWER_OUTPUT_FIXED)
238 Radio.SetOutputPower(POWER_OUTPUT_FIXED);
239 #elif defined(POWER_OUTPUT_VALUES) && defined(TARGET_TX)
240 Radio.SetOutputPower(powerValues[Power - MinPower] + powerCaliValues[Power]);
241 #elif defined(TARGET_RX)
242 // Set to max power for telemetry on the RX if not specified
243 Radio.SetOutputPowerMax();
244 #else
245 #error "[ERROR] Unknown power management!"
246 #endif
247 CurrentPower = Power;
248 updateFan();