[go: nahoru, domu]

Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

VTX SPI output calibration routine and initial PWM value config #2515

Merged
merged 2 commits into from
Jan 24, 2024
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Next Next commit
Added VTX initial PWM values
  • Loading branch information
phobos- committed Jan 3, 2024
commit 5ab5f37fa4e40a996c80f27696617be17577a2c2
2 changes: 2 additions & 0 deletions src/html/hardware.html
Original file line number Diff line number Diff line change
Expand Up @@ -286,6 +286,8 @@ <h1><b>ExpressLRS</b></h1>
<tr><td></td><td>SPI MOSI pin<img class="icon-output"/></td><td><input size='3' id='vtx_mosi' name='vtx_mosi' type='text'/></td><td>MOSI pin on RTC6705 VTx (leave undefined if sharing Radio SPI bus)</td></tr>
<tr><td></td><td>25mW VPD interpolation values</td><td><input size='40' id='vtx_amp_vpd_25mW' name='vtx_amp_vpd_25mW' type='text' class='array'/></td><td>4 values for 5650, 5750, 5850, 5950 frequencies at 25mW</td></tr>
<tr><td></td><td>100mW VPD interpolation values</td><td><input size='40' id='vtx_amp_vpd_100mW' name='vtx_amp_vpd_100mW' type='text' class='array'/></td><td>4 values for 5650, 5750, 5850, 5950 frequencies at 100mW</td></tr>
<tr><td></td><td>25mW PWM interpolation values</td><td><input size='40' id='vtx_amp_pwm_25mW' name='vtx_amp_pwm_25mW' type='text' class='array'/></td><td>4 values for 5650, 5750, 5850, 5950 frequencies at 25mW</td></tr>
<tr><td></td><td>100mW PWM interpolation values</td><td><input size='40' id='vtx_amp_pwm_100mW' name='vtx_amp_pwm_100mW' type='text' class='array'/></td><td>4 values for 5650, 5750, 5850, 5950 frequencies at 100mW</td></tr>

<tr><td colspan='2'><b>I2C</td></tr>
<tr><td></td><td>SCL pin<img class="icon-output"/></td><td><input size='3' id='i2c_scl' name='i2c_scl' type='text'/></td><td>I2C clock pin used to communicate with I2C devices</td></tr>
Expand Down
2 changes: 2 additions & 0 deletions src/include/hardware.h
Original file line number Diff line number Diff line change
Expand Up @@ -137,6 +137,8 @@ typedef enum {
HARDWARE_vtx_sck,
HARDWARE_vtx_amp_vpd_25mW,
HARDWARE_vtx_amp_vpd_100mW,
HARDWARE_vtx_amp_pwm_25mW,
HARDWARE_vtx_amp_pwm_100mW,

HARDWARE_LAST
} nameType;
Expand Down
4 changes: 3 additions & 1 deletion src/include/target/Unified_ESP32_TX.h
Original file line number Diff line number Diff line change
Expand Up @@ -202,6 +202,8 @@ GPIO_PIN_RF_AMP_PWM
GPIO_PIN_RF_AMP_VPD
GPIO_PIN_RF_AMP_VREF
GPIO_PIN_SPI_VTX_NSS
VPD_VALUES_100MW
VPD_VALUES_25MW
VPD_VALUES_100MW
PWM_VALUES_25MW
PWM_VALUES_100MW
*/
2 changes: 2 additions & 0 deletions src/include/target/Unified_ESP_RX.h
Original file line number Diff line number Diff line change
Expand Up @@ -141,4 +141,6 @@
#define GPIO_PIN_SPI_VTX_SCK hardware_pin(HARDWARE_vtx_sck)
#define VPD_VALUES_25MW hardware_u16_array(HARDWARE_vtx_amp_vpd_25mW)
#define VPD_VALUES_100MW hardware_u16_array(HARDWARE_vtx_amp_vpd_100mW)
#define PWM_VALUES_25MW hardware_u16_array(HARDWARE_vtx_amp_pwm_25mW)
#define PWM_VALUES_100MW hardware_u16_array(HARDWARE_vtx_amp_pwm_100mW)
#endif
2 changes: 1 addition & 1 deletion src/lib/MSPVTX/devMSPVTX.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -219,7 +219,7 @@ void mspVtxProcessPacket(uint8_t *packet)
power = 1;
}

if (power >= NUM_POWER_LEVELS)
if (power > NUM_POWER_LEVELS)
{
power = 3; // 25 mW
}
Expand Down
2 changes: 2 additions & 0 deletions src/lib/OPTIONS/hardware.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -129,6 +129,8 @@ static const struct {
{HARDWARE_vtx_sck, "vtx_sck", INT},
{HARDWARE_vtx_amp_vpd_25mW, "vtx_amp_vpd_25mW", ARRAY},
{HARDWARE_vtx_amp_vpd_100mW, "vtx_amp_vpd_100mW", ARRAY},
{HARDWARE_vtx_amp_pwm_25mW, "vtx_amp_pwm_25mW", ARRAY},
{HARDWARE_vtx_amp_pwm_100mW, "vtx_amp_pwm_100mW", ARRAY},
};

typedef union {
Expand Down
37 changes: 36 additions & 1 deletion src/lib/VTXSPI/devVTXSPI.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,9 +65,13 @@ static bool stopVtxMonitoring = false;
#if defined(TARGET_UNIFIED_RX)
const uint16_t *VpdSetPointArray25mW = nullptr;
const uint16_t *VpdSetPointArray100mW = nullptr;
const uint16_t *PwmArray25mW = nullptr;
const uint16_t *PwmArray100mW = nullptr;
#else
uint16_t VpdSetPointArray25mW[] = VPD_VALUES_25MW;
uint16_t VpdSetPointArray100mW[] = VPD_VALUES_100MW;
uint16_t PwmArray25mW[] = PWM_VALUES_25MW;
uint16_t PwmArray100mW[] = PWM_VALUES_100MW;
#endif

uint16_t VpdFreqArray[] = {5650, 5750, 5850, 5950};
Expand Down Expand Up @@ -203,29 +207,60 @@ static uint16_t LinearInterpVpdSetPointArray(const uint16_t VpdSetPointArray[])
return newVpd;
}

static uint16_t LinearInterpSetPwm(const uint16_t PwmArray[])
{
uint16_t newPwm = 0;

if (vtxSPIFrequencyCurrent <= VpdFreqArray[0])
{
newPwm = PwmArray[0];
}
else if (vtxSPIFrequencyCurrent >= VpdFreqArray[VpdSetPointCount - 1])
{
newPwm = PwmArray[VpdSetPointCount - 1];
}
else
{
for (uint8_t i = 0; i < (VpdSetPointCount - 1); i++)
{
if (vtxSPIFrequencyCurrent < VpdFreqArray[i + 1])
{
newPwm = PwmArray[i] + ((PwmArray[i + 1]-PwmArray[i])/(VpdFreqArray[i + 1]-VpdFreqArray[i])) * (vtxSPIFrequencyCurrent - VpdFreqArray[i]);
}
}
}

return newPwm;
}

static void SetVpdSetPoint()
{
switch (vtxSPIPowerIdx)
{
case 1: // 0 mW
VpdSetPoint = VPD_SETPOINT_0_MW;
vtxSPIPWM = vtxMaxPWM;
break;

case 2: // RCE
case 3: // 25 mW
VpdSetPoint = LinearInterpVpdSetPointArray(VpdSetPointArray25mW);
vtxSPIPWM = LinearInterpSetPwm(PwmArray25mW);
break;

case 4: // 100 mW
VpdSetPoint = LinearInterpVpdSetPointArray(VpdSetPointArray100mW);
vtxSPIPWM = LinearInterpSetPwm(PwmArray100mW);
break;

default: // YOLO mW
VpdSetPoint = VPD_SETPOINT_YOLO_MW;
vtxSPIPWM = vtxMinPWM;
break;
}

DBGLN("Setting new VPD setpoint: %d", VpdSetPoint);
setPWM();
DBGLN("Setting new VPD setpoint: %d, initial PWM: %d", VpdSetPoint, vtxSPIPWM);
}

static void checkOutputPower()
Expand Down