Allow LR1121 single RF path (#2998)
[ExpressLRS.git] / src / lib / POWERMGNT / POWERMGNT.cpp
blob31875e3d36ec76950884f9cd0bb87f702266089b
1 #include "targets.h"
2 #include "logging.h"
3 #include "POWERMGNT.h"
5 uint8_t powerToCrsfPower(PowerLevels_e Power)
7 // Crossfire's power levels as defined in opentx:radio/src/telemetry/crossfire.cpp
8 //static const int32_t power_values[] = { 0, 10, 25, 100, 500, 1000, 2000, 250, 50 };
9 switch (Power)
11 case PWR_10mW: return 1;
12 case PWR_25mW: return 2;
13 case PWR_50mW: return 8;
14 case PWR_100mW: return 3;
15 case PWR_250mW: return 7;
16 case PWR_500mW: return 4;
17 case PWR_1000mW: return 5;
18 case PWR_2000mW: return 6;
19 default:
20 return 0;
24 PowerLevels_e crsfpowerToPower(uint8_t crsfpower)
26 switch (crsfpower)
28 case 1: return PWR_10mW;
29 case 2: return PWR_25mW;
30 case 3: return PWR_100mW;
31 case 4: return PWR_500mW;
32 case 5: return PWR_1000mW;
33 case 6: return PWR_2000mW;
34 case 7: return PWR_250mW;
35 case 8: return PWR_50mW;
36 default:
37 return PWR_10mW;
41 #ifndef UNIT_TEST
43 #include "common.h"
44 #include "device.h"
45 #include "DAC.h"
46 #include "helpers.h"
49 * Moves the power management values and special cases out of the main code and into `targets.h`.
51 * TX Targets
52 * ***********
54 * A new target now just needs to define
55 * - `MinPower`, the minimum power level supported
56 * - `MaxPower`, the absolute maximum power level supported
57 * - optionally `HighPower`, if defined then module uses this as max unless `UNLOCK_HIGHER_POWER` is defined by the user
58 * - `POWER_OUTPUT_VALUES` array of values to be used to set appropriate power level from `MinPower` to `MaxPower`
60 * A target can also define one of the following to configure how the output power is set, the value given to the function
61 * is the value from the `POWER_OUTPUT_VALUES` array.
63 * - `POWER_OUTPUT_DAC` to use i2c DAC specify the address of the DAC in this define
64 * - `POWER_OUTPUT_DACWRITE` to use `dacWrite` function
65 * - `POWER_OUTPUT_ANALOG` to use `analogWrite` function
66 * - `POWER_OUTPUT_FIXED` which will provide the value to `Radio.SetOutputPower` function
67 * - default is to use `Radio.SetOutputPower` function
69 * RX Targets
70 * **********
72 * Can define `POWER_OUTPUT_FIXED` which will provide the value to `Radio.SetOutputPower` function.
73 * If nothing is defined then the default method `Radio.SetOutputPowerMax` will be used, which sets the value to
74 * 13 on SX1280 (~12.5dBm) or 15 on SX127x (~17dBm)
77 PowerLevels_e PowerLevelContainer::CurrentPower = PWR_COUNT; // default "undefined" initial value
78 PowerLevels_e POWERMGNT::FanEnableThreshold = PWR_250mW;
79 int8_t POWERMGNT::CurrentSX1280Power = 0;
81 #if defined(TARGET_UNIFIED_TX) || defined(TARGET_UNIFIED_RX)
82 static const int16_t *powerValues;
83 static const int16_t *powerValuesDual;
84 #else
85 #if defined(POWER_OUTPUT_VALUES)
86 static const int16_t powerValues[] = POWER_OUTPUT_VALUES;
87 #if defined(POWER_OUTPUT_DAC) && !defined(TARGET_UNIFIED_TX) && !defined(TARGET_UNIFIED_RX)
88 static const int16_t powerValues868[] = POWER_OUTPUT_VALUES_868;
89 extern bool isDomain868();
90 #endif
91 #else
92 static const int16_t *powerValues = nullptr;
93 #endif
94 #endif
96 static int8_t powerCaliValues[PWR_COUNT] = {0};
98 #if defined(PLATFORM_ESP32)
99 nvs_handle POWERMGNT::handle = 0;
100 #endif
102 PowerLevels_e POWERMGNT::incPower()
104 if (CurrentPower < getMaxPower())
106 setPower((PowerLevels_e)((uint8_t)CurrentPower + 1));
108 return CurrentPower;
111 PowerLevels_e POWERMGNT::decPower()
113 if (CurrentPower > MinPower)
115 setPower((PowerLevels_e)((uint8_t)CurrentPower - 1));
117 return CurrentPower;
120 void POWERMGNT::incSX1280Output()
122 // Power adjustment is capped to within +-3dB of the target power level to prevent power run-away
123 if (CurrentSX1280Power < 13 && CurrentSX1280Power < powerValues[CurrentPower] + 3)
125 CurrentSX1280Power++;
126 Radio.SetOutputPower(CurrentSX1280Power);
130 void POWERMGNT::decSX1280Output()
132 // Power adjustment is capped to within +-3dB of the target power level to prevent power run-away
133 if (CurrentSX1280Power > -18 && CurrentSX1280Power > powerValues[CurrentPower] - 3)
135 CurrentSX1280Power--;
136 Radio.SetOutputPower(CurrentSX1280Power);
140 int8_t POWERMGNT::currentSX1280Output()
142 return CurrentSX1280Power;
145 uint8_t POWERMGNT::getPowerIndBm()
147 switch (CurrentPower)
149 case PWR_10mW: return 10;
150 case PWR_25mW: return 14;
151 case PWR_50mW: return 17;
152 case PWR_100mW: return 20;
153 case PWR_250mW: return 24;
154 case PWR_500mW: return 27;
155 case PWR_1000mW: return 30;
156 case PWR_2000mW: return 33;
157 default:
158 return 0;
162 void POWERMGNT::SetPowerCaliValues(int8_t *values, size_t size)
164 bool isUpdate = false;
165 for(size_t i=0 ; i<size ; i++)
167 if(powerCaliValues[i] != values[i])
169 powerCaliValues[i] = values[i];
170 isUpdate = true;
173 #if defined(PLATFORM_ESP32)
174 if (isUpdate)
176 nvs_set_blob(handle, "powercali", &powerCaliValues, sizeof(powerCaliValues));
178 nvs_commit(handle);
179 #else
180 UNUSED(isUpdate);
181 #endif
184 void POWERMGNT::GetPowerCaliValues(int8_t *values, size_t size)
186 for(size_t i=0 ; i<size ; i++)
188 *(values + i) = powerCaliValues[i];
192 void POWERMGNT::LoadCalibration()
194 #if defined(PLATFORM_ESP32)
195 // Initialize NVS
196 esp_err_t err = nvs_flash_init();
197 if (err == ESP_ERR_NVS_NO_FREE_PAGES || err == ESP_ERR_NVS_NEW_VERSION_FOUND)
199 ESP_ERROR_CHECK(nvs_flash_erase());
200 err = nvs_flash_init();
202 ESP_ERROR_CHECK( err );
203 ESP_ERROR_CHECK(nvs_open("PWRCALI", NVS_READWRITE, &handle));
205 uint32_t version;
206 if(nvs_get_u32(handle, "calversion", &version) != ESP_ERR_NVS_NOT_FOUND
207 && version == (uint32_t)(CALIBRATION_VERSION | CALIBRATION_MAGIC))
209 size_t size = sizeof(powerCaliValues);
210 nvs_get_blob(handle, "powercali", &powerCaliValues, &size);
212 else
214 nvs_set_blob(handle, "powercali", &powerCaliValues, sizeof(powerCaliValues));
215 nvs_set_u32(handle, "calversion", CALIBRATION_VERSION | CALIBRATION_MAGIC);
216 nvs_commit(handle);
218 #else
219 memset(powerCaliValues, 0, sizeof(powerCaliValues));
220 #endif
224 void POWERMGNT::init()
226 PowerLevelContainer::CurrentPower = PWR_COUNT;
228 #if defined(TARGET_UNIFIED_TX) || defined(TARGET_UNIFIED_RX)
229 powerValues = POWER_OUTPUT_VALUES;
230 if (POWER_OUTPUT_VALUES_DUAL != nullptr)
232 powerValuesDual = POWER_OUTPUT_VALUES_DUAL;
234 #endif
235 #if defined(POWER_OUTPUT_DAC)
236 TxDAC.init();
237 #elif defined(POWER_OUTPUT_ANALOG)
238 //initialize both 12 bit DACs
239 pinMode(GPIO_PIN_RFamp_APC1, OUTPUT);
240 pinMode(GPIO_PIN_RFamp_APC2, OUTPUT);
241 analogWriteResolution(12);
243 // WARNING: The two calls to analogWrite below are needed for the
244 // lite pro, as it seems that the very first calls to analogWrite
245 // fail for an unknown reason (suspect Arduino lib bug). These
246 // set power to 50mW, which should get overwitten shortly after
247 // boot by whatever is set in the EEPROM. @wvarty
248 analogWrite(GPIO_PIN_RFamp_APC1, 3350); //0-4095 2.7V
249 analogWrite(GPIO_PIN_RFamp_APC2, 950);
250 #endif
251 LoadCalibration();
252 setDefaultPower();
255 PowerLevels_e POWERMGNT::getDefaultPower()
257 if (MinPower > DefaultPower)
259 return MinPower;
261 if (getMaxPower() < DefaultPower)
263 return getMaxPower();
265 return DefaultPower;
268 void POWERMGNT::setDefaultPower()
270 setPower(getDefaultPower());
273 void POWERMGNT::setPower(PowerLevels_e Power)
275 Power = constrain(Power, getMinPower(), getMaxPower());
276 if (Power == CurrentPower)
277 return;
279 #if defined(POWER_OUTPUT_DAC)
280 // DAC is used e.g. for R9M, ES915TX and Voyager
281 int mV = isDomain868() ? powerValues868[Power - MinPower] :powerValues[Power - MinPower];
282 TxDAC.setPower(mV);
283 #elif defined(POWER_OUTPUT_ANALOG)
284 //Set DACs PA5 & PA4
285 analogWrite(GPIO_PIN_RFamp_APC1, 3350); //0-4095 2.7V
286 analogWrite(GPIO_PIN_RFamp_APC2, powerValues[Power - MinPower]);
287 #else
288 #if defined(PLATFORM_ESP32)
289 if (POWER_OUTPUT_DACWRITE && POWER_OUTPUT_VALUES != nullptr)
291 if (POWER_OUTPUT_VALUES2 != nullptr)
293 Radio.SetOutputPower(POWER_OUTPUT_VALUES2[Power - MinPower]);
295 #if defined(PLATFORM_ESP32_S3) || defined(PLATFORM_ESP32_C3)
296 ERRLN("ESP32-S3 does not have a DAC");
297 #else
298 dacWrite(GPIO_PIN_RFamp_APC2, powerValues[Power - MinPower]);
299 #endif
301 else
302 #endif
303 if (POWER_OUTPUT_FIXED != -99)
305 Radio.SetOutputPower(POWER_OUTPUT_FIXED);
307 else if (powerValues != nullptr)
309 CurrentSX1280Power = powerValues[Power - MinPower] + powerCaliValues[Power];
310 Radio.SetOutputPower(CurrentSX1280Power);
312 #endif
314 #if defined(RADIO_LR1121)
315 if (POWER_OUTPUT_VALUES_DUAL != nullptr)
317 Radio.SetOutputPower(powerValuesDual[Power - MinPower], false); // Set the high frequency power setting.
319 #endif
321 CurrentPower = Power;
322 devicesTriggerEvent();
325 #endif /* !UNIT_TEST */