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 };
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;
24 PowerLevels_e
crsfPowerToPower(uint8_t 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
;
48 * Moves the power management values and special cases out of the main code and into `targets.h`.
53 * A new target now just needs to define
54 * - `MinPower`, the minimum power level supported
55 * - `MaxPower`, the absolute maximum power level supported
56 * - `POWER_OUTPUT_VALUES` array of values to be used to set appropriate power level from `MinPower` to `MaxPower`
58 * A target can also define one of the following to configure how the output power is set, the value given to the function
59 * is the value from the `POWER_OUTPUT_VALUES` array.
61 * - `POWER_OUTPUT_DAC` to use i2c DAC specify the address of the DAC in this define
62 * - `POWER_OUTPUT_DACWRITE` to use `dacWrite` function
63 * - `POWER_OUTPUT_ANALOG` to use `analogWrite` function
64 * - `POWER_OUTPUT_FIXED` which will provide the value to `Radio.SetOutputPower` function
65 * - default is to use `Radio.SetOutputPower` function
70 * Can define `POWER_OUTPUT_FIXED` which will provide the value to `Radio.SetOutputPower` function.
71 * If nothing is defined then the default method `Radio.SetOutputPowerMax` will be used, which sets the value to
72 * 13 on SX1280 (~12.5dBm) or 15 on SX127x (~17dBm)
75 PowerLevels_e
PowerLevelContainer::CurrentPower
= PWR_COUNT
; // default "undefined" initial value
76 PowerLevels_e
POWERMGNT::FanEnableThreshold
= PWR_250mW
;
77 int8_t POWERMGNT::CurrentSX1280Power
= 0;
79 static const int16_t *powerValues
;
80 static const int16_t *powerValuesDual
;
82 static int8_t powerCaliValues
[PWR_COUNT
] = {0};
84 #if defined(PLATFORM_ESP32)
85 nvs_handle
POWERMGNT::handle
= 0;
88 PowerLevels_e
POWERMGNT::incPower()
90 if (CurrentPower
< getMaxPower())
92 setPower((PowerLevels_e
)((uint8_t)CurrentPower
+ 1));
97 PowerLevels_e
POWERMGNT::decPower()
99 if (CurrentPower
> MinPower
)
101 setPower((PowerLevels_e
)((uint8_t)CurrentPower
- 1));
106 void POWERMGNT::incSX1280Output()
108 // Power adjustment is capped to within +-3dB of the target power level to prevent power run-away
109 if (CurrentSX1280Power
< 13 && CurrentSX1280Power
< powerValues
[CurrentPower
] + 3)
111 CurrentSX1280Power
++;
112 Radio
.SetOutputPower(CurrentSX1280Power
);
116 void POWERMGNT::decSX1280Output()
118 // Power adjustment is capped to within +-3dB of the target power level to prevent power run-away
119 if (CurrentSX1280Power
> -18 && CurrentSX1280Power
> powerValues
[CurrentPower
] - 3)
121 CurrentSX1280Power
--;
122 Radio
.SetOutputPower(CurrentSX1280Power
);
126 int8_t POWERMGNT::currentSX1280Output()
128 return CurrentSX1280Power
;
131 uint8_t POWERMGNT::getPowerIndBm()
133 switch (CurrentPower
)
135 case PWR_10mW
: return 10;
136 case PWR_25mW
: return 14;
137 case PWR_50mW
: return 17;
138 case PWR_100mW
: return 20;
139 case PWR_250mW
: return 24;
140 case PWR_500mW
: return 27;
141 case PWR_1000mW
: return 30;
142 case PWR_2000mW
: return 33;
148 void POWERMGNT::SetPowerCaliValues(int8_t *values
, size_t size
)
150 bool isUpdate
= false;
151 for(size_t i
=0 ; i
<size
; i
++)
153 if(powerCaliValues
[i
] != values
[i
])
155 powerCaliValues
[i
] = values
[i
];
159 #if defined(PLATFORM_ESP32)
162 nvs_set_blob(handle
, "powercali", &powerCaliValues
, sizeof(powerCaliValues
));
170 void POWERMGNT::GetPowerCaliValues(int8_t *values
, size_t size
)
172 for(size_t i
=0 ; i
<size
; i
++)
174 *(values
+ i
) = powerCaliValues
[i
];
178 void POWERMGNT::LoadCalibration()
180 #if defined(PLATFORM_ESP32)
182 esp_err_t err
= nvs_flash_init();
183 if (err
== ESP_ERR_NVS_NO_FREE_PAGES
|| err
== ESP_ERR_NVS_NEW_VERSION_FOUND
)
185 ESP_ERROR_CHECK(nvs_flash_erase());
186 err
= nvs_flash_init();
188 ESP_ERROR_CHECK( err
);
189 ESP_ERROR_CHECK(nvs_open("PWRCALI", NVS_READWRITE
, &handle
));
192 if(nvs_get_u32(handle
, "calversion", &version
) != ESP_ERR_NVS_NOT_FOUND
193 && version
== (uint32_t)(CALIBRATION_VERSION
| CALIBRATION_MAGIC
))
195 size_t size
= sizeof(powerCaliValues
);
196 nvs_get_blob(handle
, "powercali", &powerCaliValues
, &size
);
200 nvs_set_blob(handle
, "powercali", &powerCaliValues
, sizeof(powerCaliValues
));
201 nvs_set_u32(handle
, "calversion", CALIBRATION_VERSION
| CALIBRATION_MAGIC
);
205 memset(powerCaliValues
, 0, sizeof(powerCaliValues
));
210 void POWERMGNT::init()
212 PowerLevelContainer::CurrentPower
= PWR_COUNT
;
214 powerValues
= POWER_OUTPUT_VALUES
;
215 if (POWER_OUTPUT_VALUES_DUAL
!= nullptr)
217 powerValuesDual
= POWER_OUTPUT_VALUES_DUAL
;
223 PowerLevels_e
POWERMGNT::getDefaultPower()
225 if (MinPower
> DefaultPower
)
229 if (getMaxPower() < DefaultPower
)
231 return getMaxPower();
236 void POWERMGNT::setDefaultPower()
238 setPower(getDefaultPower());
241 void POWERMGNT::setPower(PowerLevels_e Power
)
243 Power
= constrain(Power
, getMinPower(), getMaxPower());
244 if (Power
== CurrentPower
)
247 if (POWER_OUTPUT_DACWRITE
)
249 if (POWER_OUTPUT_VALUES2
!= nullptr)
251 Radio
.SetOutputPower(POWER_OUTPUT_VALUES2
[Power
- MinPower
]);
253 #if defined(PLATFORM_ESP32_S3) || defined(PLATFORM_ESP32_C3) || defined(PLATFORM_ESP8266)
254 ERRLN("ESP32-S3/C3 and ESP8285 MCUs do not have a DAC");
256 dacWrite(GPIO_PIN_RFamp_APC2
, powerValues
[Power
- MinPower
]);
261 CurrentSX1280Power
= powerValues
[Power
- MinPower
] + powerCaliValues
[Power
];
262 Radio
.SetOutputPower(CurrentSX1280Power
);
265 #if defined(RADIO_LR1121)
266 if (POWER_OUTPUT_VALUES_DUAL
!= nullptr)
268 Radio
.SetOutputPower(powerValuesDual
[Power
- MinPower
], false); // Set the high frequency power setting.
272 CurrentPower
= Power
;
273 devicesTriggerEvent();
276 #endif /* !UNIT_TEST */