Add support for VTX output power attenuation, Fix timerHardware definition

This commit is contained in:
Evgeny Sychov 2016-06-16 01:34:01 -07:00
parent 39d8e87759
commit d73f28fe94
7 changed files with 28 additions and 9 deletions

View File

@ -435,6 +435,7 @@ static void resetConf(void)
#ifdef USE_RTC6705
masterConfig.vtx_channel = 19; // default to Boscam E channel 4
masterConfig.vtx_power = 1;
#endif
#ifdef BOARD_HAS_VOLTAGE_DIVIDER

View File

@ -127,6 +127,7 @@ typedef struct master_t {
#ifdef USE_RTC6705
uint8_t vtx_channel;
uint8_t vtx_power;
#endif
#ifdef OSD

View File

@ -148,4 +148,9 @@ void rtc6705_soft_spi_set_channel(uint16_t channel_freq) {
rtc6705_write_register(0, 400);
rtc6705_write_register(1, (N << 7) | A);
}
void rtc6705_soft_spi_set_rf_power(uint8_t power) {
rtc6705_write_register(7, (power ? PA_CONTROL_DEFAULT : (PA_CONTROL_DEFAULT | PD_Q5G_MASK) & (~(PA5G_PW_MASK | PA5G_BS_MASK))));
}
#endif

View File

@ -17,9 +17,21 @@
#pragma once
#define DP_5G_MASK 0x7000
#define PA5G_BS_MASK 0x0E00
#define PA5G_PW_MASK 0x0180
#define PD_Q5G_MASK 0x0040
#define QI_5G_MASK 0x0038
#define PA_BS_MASK 0x0007
#define PA_CONTROL_DEFAULT 0x4FBD
extern char* vtx_bands[];
extern uint16_t vtx_freq[];
extern uint16_t current_vtx_channel;
void rtc6705_soft_spi_init(void);
void rtc6705_soft_spi_set_channel(uint16_t channel_freq);
void rtc6705_soft_spi_set_rf_power(uint8_t power);

View File

@ -22,7 +22,7 @@
#include <math.h>
#include "platform.h"
#include "scheduler.h"
#include "scheduler/scheduler.h"
#include "common/axis.h"
#include "common/color.h"
@ -47,7 +47,6 @@
#include "drivers/pwm_rx.h"
#include "drivers/adc.h"
#include "drivers/bus_i2c.h"
#include "drivers/bus_bst.h"
#include "drivers/bus_spi.h"
#include "drivers/inverter.h"
#include "drivers/flash_m25p16.h"
@ -111,7 +110,6 @@
#include "drivers/vtx_soft_spi_rtc6705.h"
#endif
#include "scheduler.h"
#include "common/printf.h"
#define MICROSECONDS_IN_A_SECOND (1000 * 1000)
@ -707,6 +705,7 @@ void osdInit(void)
rtc6705_soft_spi_init();
current_vtx_channel = masterConfig.vtx_channel;
rtc6705_soft_spi_set_channel(vtx_freq[current_vtx_channel]);
rtc6705_soft_spi_set_rf_power(masterConfig.vtx_power);
#endif
max7456_init(masterConfig.osdProfile.system);

View File

@ -806,6 +806,7 @@ const clivalue_t valueTable[] = {
#endif
#ifdef USE_RTC6705
{ "vtx_channel", VAR_INT16 | MASTER_VALUE, &masterConfig.vtx_channel, .config.minmax = { 0, 39 } },
{ "vtx_power", VAR_UINT8 | MASTER_VALUE, &masterConfig.vtx_power, .config.minmax = { 0, 1 } },
#endif
#ifdef OSD
{ "osd_system", VAR_UINT8 | MASTER_VALUE, &masterConfig.osdProfile.system, .config.minmax = { 0, 2 } },

View File

@ -49,13 +49,13 @@ const uint16_t airPWM[] = {
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM4, GPIOB, Pin_6, TIM_Channel_1, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource6, GPIO_AF_2, 0}, // PWM1 - PB6
{ TIM4, GPIOB, Pin_7, TIM_Channel_2, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource7, GPIO_AF_2, 0}, // PWM2 - PB6
{ TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_2, 0}, // PWM3 - PB8
{ TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource9, GPIO_AF_2, 0}, // PWM4 - PB9
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM1 - PB6
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM2 - PB6
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM3 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM4 - PB9
{ TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_2, 0}, // PWM5 - PB0 - *TIM3_CH3
{ TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_2, 0}, // PWM6 - PB1 - *TIM3_CH4
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM5 - PB0 - *TIM3_CH3
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM6 - PB1 - *TIM3_CH4
};