Skip to content

Commit

Permalink
need to measure output, also start on other rxes
Browse files Browse the repository at this point in the history
add the other rxes
  • Loading branch information
StonedDawg committed Feb 2, 2022
1 parent 6fef79b commit 9a51be3
Show file tree
Hide file tree
Showing 12 changed files with 54 additions and 18 deletions.
3 changes: 2 additions & 1 deletion src/include/target/AXIS_THOR_2400_RX.h
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
#define GPIO_PIN_ANTENNA_SELECT 0 // Low = Ant1, High = Ant2, pulled high by external resistor
#endif

// Output Power - use default SX1280
#define POWER_OUTPUT_MAX 13 // -10=10mW, -6=25mW, -3=50mW, 1=100mW
#define POWER_OUTPUT_MIN -10 // -10=10mW, -6=25mW, -3=50mW, 1=100mW

#define Regulatory_Domain_ISM_2400 1
3 changes: 2 additions & 1 deletion src/include/target/BETAFPV_2400_RX.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#define GPIO_PIN_TX_ENABLE 10

// Output Power
#define POWER_OUTPUT_FIXED 1 // -10=10mW, -6=25mW, -3=50mW, 1=100mW
#define POWER_OUTPUT_MAX 1 // -10=10mW, -6=25mW, -3=50mW, 1=100mW
#define POWER_OUTPUT_MIN -10 // -10=10mW, -6=25mW, -3=50mW, 1=100mW

#define Regulatory_Domain_ISM_2400 1
7 changes: 2 additions & 5 deletions src/include/target/FM30_RX_MINI.h
Original file line number Diff line number Diff line change
Expand Up @@ -47,11 +47,8 @@
#define MaxPower PWR_250mW
#define POWER_OUTPUT_VALUES {-15,-11,-7,-1,6}
#else
#ifdef UNLOCK_HIGHER_POWER
#define POWER_OUTPUT_FIXED 6 // 250mW (uses values as above)
#else
#define POWER_OUTPUT_FIXED -1 // 100mW (uses values as above)
#endif
#define POWER_OUTPUT_MAX 6 // 250mW (uses values as above)
#define POWER_OUTPUT_MIN -15 // 100mW (uses values as above)
#endif

#define Regulatory_Domain_ISM_2400 1
3 changes: 2 additions & 1 deletion src/include/target/MATEK_2400_RX.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
#endif

// Output Power
#define POWER_OUTPUT_FIXED 3
#define POWER_OUTPUT_MAX 3
#define POWER_OUTPUT_MIN -10

#define Regulatory_Domain_ISM_2400 1
3 changes: 2 additions & 1 deletion src/include/target/Vantac_2400_RX.h
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
#define GPIO_PIN_TX_ENABLE 10

// Output Power
#define POWER_OUTPUT_FIXED 1 // -10=10mW, -6=25mW, -3=50mW, 1=100mW
#define POWER_OUTPUT_MAX 1
#define POWER_OUTPUT_MIN -10

#define Regulatory_Domain_ISM_2400 1
3 changes: 2 additions & 1 deletion src/include/target/iFlight_2400_RX.h
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
#define GPIO_PIN_BUTTON 0

// Output Power
#define POWER_OUTPUT_FIXED 3
#define POWER_OUTPUT_MAX 3
#define POWER_OUTPUT_MIN -10

#define Regulatory_Domain_ISM_2400 1
7 changes: 7 additions & 0 deletions src/lib/LUA/rx_devLUA.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
#include "device.h"

#include "CRSF.h"
#include "POWERMGNT.h"
#include "config.h"
#include "logging.h"
#include "lua.h"
Expand Down Expand Up @@ -51,6 +52,7 @@ static struct luaItem_command luaRxWebUpdate = {
//---------------------------- WiFi -----------------------------


extern POWERMGNT POWERMGNT;
extern RxConfig config;
#if defined(PLATFORM_ESP32) || defined(PLATFORM_ESP8266)
extern unsigned long rebootTime;
Expand All @@ -70,6 +72,11 @@ static void registerLuaParameters()

registerLUAParameter(&luaTlmPower, [](uint8_t id, uint8_t arg){
config.SetPower(arg);
if(arg == 0){
POWERMGNT.setPower(MinPower);
} else {
POWERMGNT.setPower(MaxPower);
}
config.Commit();
devicesTriggerEvent();
});
Expand Down
19 changes: 16 additions & 3 deletions src/lib/POWERMGNT/POWERMGNT.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -241,6 +241,7 @@ void POWERMGNT::setDefaultPower()

void POWERMGNT::setPower(PowerLevels_e Power)
{
#ifdef TARGET_TX
if (Power == CurrentPower)
return;

Expand All @@ -252,7 +253,7 @@ void POWERMGNT::setPower(PowerLevels_e Power)
{
Power = MaxPower;
}

#endif
#if defined(POWER_OUTPUT_DAC)
// DAC is used e.g. for R9M, ES915TX and Voyager
Radio.SetOutputPower(0b0000);
Expand All @@ -265,14 +266,26 @@ void POWERMGNT::setPower(PowerLevels_e Power)
#elif defined(POWER_OUTPUT_DACWRITE)
Radio.SetOutputPower(0b0000);
dacWrite(GPIO_PIN_RFamp_APC2, powerValues[Power - MinPower]);
#elif defined(POWER_OUTPUT_FIXED)
#elif defined(POWER_OUTPUT_FIXED) && defined(TARGET_TX)
Radio.SetOutputPower(POWER_OUTPUT_FIXED);
#elif defined(POWER_OUTPUT_VALUES) && defined(TARGET_TX)
CurrentSX1280Power = powerValues[Power - MinPower] + powerCaliValues[Power];
Radio.SetOutputPower(CurrentSX1280Power);
#elif defined(TARGET_RX)
// Set to max power for telemetry on the RX if not specified
Radio.SetOutputPowerMax();
if (Power == CurrentPower)
return;

if (Power <= MinPower)
{
Power = MinPower;
Radio.SetOutputPowerMin();
}
else if (Power >= MaxPower)
{
Power = MaxPower;
Radio.SetOutputPowerMax();
}
#else
#error "[ERROR] Unknown power management!"
#endif
Expand Down
2 changes: 1 addition & 1 deletion src/lib/POWERMGNT/POWERMGNT.h
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
#if defined(TARGET_RX)
// These are "fake" values as the power on the RX is not user selectable
#define MinPower PWR_10mW
#define MaxPower PWR_10mW
#define MaxPower PWR_25mW
#endif

#if defined(HighPower) && !defined(UNLOCK_HIGHER_POWER)
Expand Down
1 change: 1 addition & 0 deletions src/lib/SX127xDriver/SX127x.h
Original file line number Diff line number Diff line change
Expand Up @@ -73,6 +73,7 @@ class SX127xDriver
void SetSyncWord(uint8_t syncWord);
void SetOutputPower(uint8_t Power);
void SetOutputPowerMax() { SetOutputPower(0b1111); };
void SetOutputPowerMin() { SetOutputPower(0b0111); }; //all rx has no RFO, this should value get around 10dbm
void SetPreambleLength(uint8_t PreambleLen);
void SetSpreadingFactor(SX127x_SpreadingFactor sf);
void SetRxTimeoutUs(uint32_t interval);
Expand Down
13 changes: 12 additions & 1 deletion src/lib/SX1280Driver/SX1280.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,15 @@
#include "SX1280_Regs.h"
#include "SX1280_hal.h"


#ifndef POWER_OUTPUT_MIN
#define POWER_OUTPUT_MIN -10
#endif
#ifndef POWER_OUTPUT_MAX
#define POWER_OUTPUT_MAX 13
#endif


class SX1280Driver
{
public:
Expand Down Expand Up @@ -71,7 +80,9 @@ class SX1280Driver
void ICACHE_RAM_ATTR SetFIFOaddr(uint8_t txBaseAddr, uint8_t rxBaseAddr);
void SetRxTimeoutUs(uint32_t interval);
void SetOutputPower(int8_t power);
void SetOutputPowerMax() { SetOutputPower(13); };

void SetOutputPowerMin() { SetOutputPower(POWER_OUTPUT_MIN); };
void SetOutputPowerMax() { SetOutputPower(POWER_OUTPUT_MAX); };

int32_t ICACHE_RAM_ATTR GetFrequencyError();

Expand Down
8 changes: 5 additions & 3 deletions src/src/rx_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1006,9 +1006,11 @@ static void setupRadio()
return;
}

// Set transmit power to maximum
POWERMGNT.setPower(MaxPower);

if(config.GetPower()>0){
POWERMGNT.setPower(MaxPower);
} else {
POWERMGNT.setPower(MinPower);
}
Radio.RXdoneCallback = &RXdoneISR;
Radio.TXdoneCallback = &TXdoneISR;

Expand Down

0 comments on commit 9a51be3

Please sign in to comment.