1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-16 21:05:35 +03:00

VTX cleanups from Cleanflight. Also some transitions to use new IO

system for VTX CS pin.  Fix missing VTX CS GPIO pin initialisation.
Ensure VTX CS is set correctly when enabling the VTX module.
Configure VTX module boot delay - 50ms in old code was too slow on some
cold boots.
VTX SPI divisor is now set each time an SPI transfer occurs so that the
VTX module can co-exist on the same SPI bus as other devices - NEO uses
MAX7456 and RTC6705 VTX on the same SPI bus.
This commit is contained in:
Hydra 2016-12-28 18:33:16 +00:00 committed by Michael Keller
parent 31030dd29d
commit aae589cab8
5 changed files with 81 additions and 40 deletions

View file

@ -84,19 +84,32 @@
#define RTC6705_SET_WRITE 0x11 //10001b to write to register
#define RTC6705_SET_DIVMULT 1000000 //Division value (to fit into a uint32_t) (Hz to MHz)
#define DISABLE_RTC6705 GPIO_SetBits(RTC6705_CS_GPIO, RTC6705_CS_PIN)
#define ENABLE_RTC6705 GPIO_ResetBits(RTC6705_CS_GPIO, RTC6705_CS_PIN)
static IO_t vtxPowerPin = IO_NONE;
static IO_t vtxCSPin = IO_NONE;
#ifdef RTC6705_POWER_PIN
static IO_t vtxPowerPin = IO_NONE;
#define DISABLE_RTC6705 IOHi(vtxCSPin)
#ifdef USE_RTC6705_CLK_HACK
// HACK for missing pull up on CLK line - drive the CLK high *before* enabling the CS pin.
#define ENABLE_RTC6705 {GPIO_SetBits(RTC6705_CLK_GPIO, RTC6705_CLK_PIN); delayMicroseconds(5); IOLo(vtxCSPin); }
#else
#define ENABLE_RTC6705 IOLo(vtxCSPin)
#endif
#define DP_5G_MASK 0x7000 // b111000000000000
#define PA5G_BS_MASK 0x0E00 // b000111000000000
#define PA5G_PW_MASK 0x0180 // b000000110000000
#define PD_Q5G_MASK 0x0040 // b000000001000000
#define QI_5G_MASK 0x0038 // b000000000111000
#define PA_BS_MASK 0x0007 // b000000000000111
#define PA_CONTROL_DEFAULT 0x4FBD
#define ENABLE_VTX_POWER IOLo(vtxPowerPin)
#define DISABLE_VTX_POWER IOHi(vtxPowerPin)
// Define variables
static const uint32_t channelArray[RTC6705_BAND_MAX][RTC6705_CHANNEL_MAX] = {
static const uint32_t channelArray[RTC6705_BAND_COUNT][RTC6705_CHANNEL_COUNT] = {
{ RTC6705_SET_A1, RTC6705_SET_A2, RTC6705_SET_A3, RTC6705_SET_A4, RTC6705_SET_A5, RTC6705_SET_A6, RTC6705_SET_A7, RTC6705_SET_A8 },
{ RTC6705_SET_B1, RTC6705_SET_B2, RTC6705_SET_B3, RTC6705_SET_B4, RTC6705_SET_B5, RTC6705_SET_B6, RTC6705_SET_B7, RTC6705_SET_B8 },
{ RTC6705_SET_E1, RTC6705_SET_E2, RTC6705_SET_E3, RTC6705_SET_E4, RTC6705_SET_E5, RTC6705_SET_E6, RTC6705_SET_E7, RTC6705_SET_E8 },
@ -104,20 +117,6 @@ static const uint32_t channelArray[RTC6705_BAND_MAX][RTC6705_CHANNEL_MAX] = {
{ RTC6705_SET_R1, RTC6705_SET_R2, RTC6705_SET_R3, RTC6705_SET_R4, RTC6705_SET_R5, RTC6705_SET_R6, RTC6705_SET_R7, RTC6705_SET_R8 },
};
/**
* Send a command and return if good
* TODO chip detect
*/
static bool rtc6705IsReady(void)
{
// Sleep a little bit to make sure it has booted
delay(50);
// TODO Do a read and get current config (note this would be reading on MOSI (data) line)
return true;
}
/**
* Reverse a uint32_t (LSB to MSB)
* This is easier for when generating the frequency to then
@ -139,7 +138,7 @@ static uint32_t reverse32(uint32_t in)
* Start chip if available
*/
bool rtc6705Init(void)
void rtc6705Init(void)
{
#ifdef RTC6705_POWER_PIN
vtxPowerPin = IOGetByTag(IO_TAG(RTC6705_POWER_PIN));
@ -149,9 +148,15 @@ bool rtc6705Init(void)
ENABLE_VTX_POWER;
#endif
vtxCSPin = IOGetByTag(IO_TAG(RTC6705_CS_PIN));
IOInit(vtxCSPin, OWNER_VTX, 0);
DISABLE_RTC6705;
spiSetDivisor(RTC6705_SPI_INSTANCE, SPI_CLOCK_SLOW);
return rtc6705IsReady();
// GPIO bit is enabled so here so the output is not pulled low when the GPIO is set in output mode.
// Note: It's critical to ensure that incorrect signals are not sent to the VTX.
IOConfigGPIO(vtxCSPin, IOCFG_OUT_PP);
delay(RTC6705_BOOT_DELAY);
}
/**
@ -170,7 +175,11 @@ static void rtc6705Transfer(uint32_t command)
spiTransferByte(RTC6705_SPI_INSTANCE, (command >> 8) & 0xFF);
spiTransferByte(RTC6705_SPI_INSTANCE, (command >> 0) & 0xFF);
delayMicroseconds(2);
DISABLE_RTC6705;
delayMicroseconds(2);
}
/**
@ -178,11 +187,13 @@ static void rtc6705Transfer(uint32_t command)
*/
void rtc6705SetChannel(uint8_t band, uint8_t channel)
{
band = constrain(band, RTC6705_BAND_MIN, RTC6705_BAND_MAX);
channel = constrain(channel, RTC6705_CHANNEL_MIN, RTC6705_CHANNEL_MAX);
band = constrain(band, 0, RTC6705_BAND_COUNT - 1);
channel = constrain(channel, 0, RTC6705_CHANNEL_COUNT - 1);
spiSetDivisor(RTC6705_SPI_INSTANCE, SPI_CLOCK_SLOW);
rtc6705Transfer(RTC6705_SET_HEAD);
rtc6705Transfer(channelArray[band-1][channel-1]);
rtc6705Transfer(channelArray[band][channel]);
}
/**
@ -202,8 +213,37 @@ void rtc6705SetFreq(uint16_t freq)
val_hex |= (val_a << 5);
val_hex |= (val_n << 12);
spiSetDivisor(RTC6705_SPI_INSTANCE, SPI_CLOCK_SLOW);
rtc6705Transfer(RTC6705_SET_HEAD);
delayMicroseconds(10);
rtc6705Transfer(val_hex);
}
void rtc6705SetRFPower(uint8_t rf_power)
{
spiSetDivisor(RTC6705_SPI_INSTANCE, SPI_CLOCK_SLOW);
uint32_t val_hex = 0x10; // write
val_hex |= 7; // address
uint32_t data = rf_power == 0 ? (PA_CONTROL_DEFAULT | PD_Q5G_MASK) & (~(PA5G_PW_MASK | PA5G_BS_MASK)) : PA_CONTROL_DEFAULT;
val_hex |= data << 5; // 4 address bits and 1 rw bit.
rtc6705Transfer(val_hex);
}
void rtc6705Disable(void)
{
#ifdef RTC6705_POWER_PIN
DISABLE_VTX_POWER;
#endif
}
void rtc6705Enable(void)
{
#ifdef RTC6705_POWER_PIN
ENABLE_VTX_POWER;
#endif
}
#endif

View file

@ -26,13 +26,16 @@
#include <stdint.h>
#define RTC6705_BAND_MIN 1
#define RTC6705_BAND_MAX 5
#define RTC6705_CHANNEL_MIN 1
#define RTC6705_CHANNEL_MAX 8
#define RTC6705_BAND_COUNT 5
#define RTC6705_CHANNEL_COUNT 8
#define RTC6705_RF_POWER_COUNT 2
#define RTC6705_FREQ_MIN 5600
#define RTC6705_FREQ_MAX 5950
bool rtc6705Init(void);
#define RTC6705_BOOT_DELAY 350 // milliseconds
void rtc6705Init(void);
void rtc6705SetChannel(uint8_t band, uint8_t channel);
void rtc6705SetFreq(uint16_t freq);
void rtc6705SetRFPower(uint8_t rf_power);

View file

@ -61,7 +61,7 @@ void vtxInit(void)
}
}
static void setChannelSaveAndNotify(uint8_t *bandOrChannel, uint8_t step, int32_t min, int32_t max)
static void setChannelSaveAndNotify(uint8_t *bandOrChannel, uint8_t step, int32_t max)
{
if (ARMING_FLAG(ARMED)) {
locked = 1;
@ -69,7 +69,7 @@ static void setChannelSaveAndNotify(uint8_t *bandOrChannel, uint8_t step, int32_
if (vtxConfig()->vtx_mode == 0 && !locked) {
uint8_t temp = (*bandOrChannel) + step;
temp = constrain(temp, min, max);
temp = constrain(temp, 0, max);
*bandOrChannel = temp;
rtc6705SetChannel(vtxConfig()->vtx_band, vtxConfig()->vtx_channel);
@ -81,22 +81,22 @@ static void setChannelSaveAndNotify(uint8_t *bandOrChannel, uint8_t step, int32_
void vtxIncrementBand(void)
{
setChannelSaveAndNotify(&(vtxConfigMutable()->vtx_band), 1, RTC6705_BAND_MIN, RTC6705_BAND_MAX);
setChannelSaveAndNotify(&(vtxConfigMutable()->vtx_band), 1, RTC6705_BAND_COUNT - 1);
}
void vtxDecrementBand(void)
{
setChannelSaveAndNotify(&(vtxConfigMutable()->vtx_band), -1, RTC6705_BAND_MIN, RTC6705_BAND_MAX);
setChannelSaveAndNotify(&(vtxConfigMutable()->vtx_band), -1, RTC6705_BAND_COUNT - 1);
}
void vtxIncrementChannel(void)
{
setChannelSaveAndNotify(&(vtxConfigMutable()->vtx_channel), 1, RTC6705_CHANNEL_MIN, RTC6705_CHANNEL_MAX);
setChannelSaveAndNotify(&(vtxConfigMutable()->vtx_channel), 1, RTC6705_CHANNEL_COUNT - 1);
}
void vtxDecrementChannel(void)
{
setChannelSaveAndNotify(&(vtxConfigMutable()->vtx_channel), -1, RTC6705_CHANNEL_MIN, RTC6705_CHANNEL_MAX);
setChannelSaveAndNotify(&(vtxConfigMutable()->vtx_channel), -1, RTC6705_CHANNEL_COUNT - 1);
}
void vtxUpdateActivatedChannel(void)

View file

@ -73,8 +73,7 @@
#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5
#define VTX
#define RTC6705_CS_GPIO GPIOA
#define RTC6705_CS_PIN GPIO_Pin_4
#define RTC6705_CS_PIN PA4
#define RTC6705_SPI_INSTANCE SPI1
#define M25P16_CS_GPIO GPIOB

View file

@ -102,8 +102,7 @@
#define SPI3_MOSI_PIN PB5
#define VTX
#define RTC6705_CS_GPIO GPIOF
#define RTC6705_CS_PIN GPIO_Pin_4
#define RTC6705_CS_PIN PF4
#define RTC6705_SPI_INSTANCE SPI3
#define RTC6705_POWER_PIN PC3