optimise mavlink SS packet size (#3029)
[ExpressLRS.git] / src / lib / POWERMGNT / POWERMGNT.h
blob4367f638b02d639cd165d99c5502c20a7f00f03f
1 #pragma once
3 #include "options.h"
5 #if defined(PLATFORM_ESP32)
6 #include <nvs_flash.h>
7 #include <nvs.h>
8 #endif
10 typedef enum
12 PWR_10mW = 0,
13 PWR_25mW = 1,
14 PWR_50mW = 2,
15 PWR_100mW = 3,
16 PWR_250mW = 4,
17 PWR_500mW = 5,
18 PWR_1000mW = 6,
19 PWR_2000mW = 7,
20 PWR_COUNT = 8,
21 PWR_MATCH_TX = PWR_COUNT,
22 } PowerLevels_e;
24 uint8_t powerToCrsfPower(PowerLevels_e Power);
25 PowerLevels_e crsfPowerToPower(uint8_t crsfpower);
27 class PowerLevelContainer
29 protected:
30 static PowerLevels_e CurrentPower;
31 public:
32 static PowerLevels_e currPower() { return CurrentPower; }
35 #ifndef UNIT_TEST
37 class POWERMGNT : public PowerLevelContainer
40 private:
41 static int8_t CurrentSX1280Power;
42 static PowerLevels_e FanEnableThreshold;
43 #if defined(PLATFORM_ESP32)
44 static nvs_handle handle;
45 #endif
46 static void LoadCalibration();
48 public:
49 /**
50 * @brief Set the power level, constrained to MinPower..MaxPower
52 * @param Power the power level to set
54 static void setPower(PowerLevels_e Power);
56 /**
57 * @brief Increment to the next higher power level, capped at MaxPower
59 * @return PowerLevels_e the new power level
61 static PowerLevels_e incPower();
63 /**
64 * @brief Decrement to the next lower power level, capped at MinPower
66 * @return PowerLevels_e the new power level
68 static PowerLevels_e decPower();
70 /**
71 * @brief Get the currently selected power level
73 * @return PowerLevels_e the currently selected power level
75 static PowerLevels_e currPower() { return CurrentPower; }
77 /**
78 * @brief Get the MinPower level supported by this device
80 * @return PowerLevels_e the minimum power level supported
82 static PowerLevels_e getMinPower() { return MinPower; }
84 /**
85 * @brief Get the MaxPower level supported by this device.
87 * @return PowerLevels_e the maximum power level supported
89 static PowerLevels_e getMaxPower() {
90 PowerLevels_e power;
91 power = MaxPower;
92 #if defined(Regulatory_Domain_EU_CE_2400)
93 if (power > PWR_100mW)
95 power = PWR_100mW;
97 #endif
98 return power;
102 * @brief Get the Default power level for this device
104 * @return PowerLevels_e the default power level
106 static PowerLevels_e getDefaultPower();
109 * @brief Set the output power to the default power level
111 static void setDefaultPower();
114 * @brief Get the currently configured power level in dBm
116 * @return uint8_t the dBm for the current power level
118 static uint8_t getPowerIndBm();
121 * @brief increment the SX1280 power level by 1 dBm, capped to 3dBm above the selected power level
123 static void incSX1280Output();
126 * @brief decrement the SX1280 power level by 1 dBm, capped to 3dBm below the selected power level
128 static void decSX1280Output();
131 * @brief Get the current value given to the SX1280 for it's output power.
132 * This value may have been adjusted up/dowm from nominal by the PDET routine, if supported
133 * by the device (i.e. modules with SKY85321 PA/LNA)
135 * @return int8_t the current (adjusted) SX1280 power level
137 static int8_t currentSX1280Output();
140 * @brief Initialise the power management subsystem.
141 * Configures PWM ouptut pins, DACs, loads power calibration settings
142 * and sets output power to the default power level as appropriate for the
143 * device
145 static void init();
147 static void SetPowerCaliValues(int8_t *values, size_t size);
148 static void GetPowerCaliValues(int8_t *values, size_t size);
152 #define CALIBRATION_MAGIC 0x43414C << 8 //['C', 'A', 'L']
153 #define CALIBRATION_VERSION 1
155 #endif /* !UNIT_TEST */