mirror of
https://github.com/juribeparada/MMDVM_HS.git
synced 2025-12-06 07:12:08 +01:00
Adding Standard TX/RX Data interface support for ADF7021 (without CLKOUT signal)
This commit is contained in:
parent
7e36722b23
commit
d1976f1049
29
ADF7021.cpp
29
ADF7021.cpp
|
|
@ -73,7 +73,13 @@ void CIO::ifConf()
|
|||
F_divider = floor(divider + 0.5);
|
||||
|
||||
ADF7021_RX_REG0 = (uint32_t) 0b0000;
|
||||
ADF7021_RX_REG0 |= (uint32_t) 0b01011 << 27; // mux regulator/uart enabled/receive
|
||||
|
||||
#if defined(BIDIR_DATA_PIN)
|
||||
ADF7021_RX_REG0 |= (uint32_t) 0b01001 << 27; // mux regulator/receive
|
||||
#else
|
||||
ADF7021_RX_REG0 |= (uint32_t) 0b01011 << 27; // mux regulator/uart-spi enabled/receive
|
||||
#endif
|
||||
|
||||
ADF7021_RX_REG0 |= (uint32_t) N_divider << 19; // frequency;
|
||||
ADF7021_RX_REG0 |= (uint32_t) F_divider << 4; // frequency;
|
||||
|
||||
|
|
@ -84,7 +90,13 @@ void CIO::ifConf()
|
|||
F_divider = floor(divider + 0.5);
|
||||
|
||||
ADF7021_TX_REG0 = (uint32_t) 0b0000; // register 0
|
||||
ADF7021_TX_REG0 |= (uint32_t) 0b01010 << 27; // mux regulator/uart enabled/transmit
|
||||
|
||||
#if defined(BIDIR_DATA_PIN)
|
||||
ADF7021_TX_REG0 |= (uint32_t) 0b01000 << 27; // mux regulator/transmit
|
||||
#else
|
||||
ADF7021_TX_REG0 |= (uint32_t) 0b01010 << 27; // mux regulator/uart-spi enabled/transmit
|
||||
#endif
|
||||
|
||||
ADF7021_TX_REG0 |= (uint32_t) N_divider << 19; // frequency;
|
||||
ADF7021_TX_REG0 |= (uint32_t) F_divider << 4; // frequency;
|
||||
|
||||
|
|
@ -235,9 +247,15 @@ void CIO::ifConf()
|
|||
//======================================================================================================================
|
||||
void CIO::setTX()
|
||||
{
|
||||
// Send register 0 for TX operation
|
||||
AD7021_control_byte = ADF7021_TX_REG0;
|
||||
Send_AD7021_control();
|
||||
|
||||
#if defined(BIDIR_DATA_PIN)
|
||||
Data_dir_out(true); // Data pin output mode
|
||||
#endif
|
||||
|
||||
// PTT pin on
|
||||
PTT_pin(HIGH);
|
||||
LED_pin(LOW);
|
||||
}
|
||||
|
|
@ -245,11 +263,18 @@ void CIO::setTX()
|
|||
//======================================================================================================================
|
||||
void CIO::setRX()
|
||||
{
|
||||
// Delay for TX latency
|
||||
delay_rx();
|
||||
|
||||
// Send register 0 for RX operation
|
||||
AD7021_control_byte = ADF7021_RX_REG0;
|
||||
Send_AD7021_control();
|
||||
|
||||
#if defined(BIDIR_DATA_PIN)
|
||||
Data_dir_out(false); // Data pin input mode
|
||||
#endif
|
||||
|
||||
// PTT pin off
|
||||
PTT_pin(LOW);
|
||||
LED_pin(HIGH);
|
||||
}
|
||||
|
|
|
|||
3
Config.h
3
Config.h
|
|
@ -22,6 +22,9 @@
|
|||
// Enable ADF7021 support:
|
||||
#define ENABLE_ADF7021
|
||||
|
||||
// Bidirectional Data pin (Enable Standard TX/RX Data Interface of ADF7021)
|
||||
#define BIDIR_DATA_PIN
|
||||
|
||||
// TCXO of the ADF7021:
|
||||
// For 14.7456 MHz:
|
||||
#define ADF7021_14_7456
|
||||
|
|
|
|||
14
IO.cpp
14
IO.cpp
|
|
@ -45,7 +45,10 @@ m_txBuffer(TX_RINGBUFFER_SIZE)
|
|||
COS_pin(LOW);
|
||||
DEB_pin(LOW);
|
||||
|
||||
#if !defined(BIDIR_DATA_PIN)
|
||||
TXD_pin(LOW);
|
||||
#endif
|
||||
|
||||
SCLK_pin(LOW);
|
||||
SDATA_pin(LOW);
|
||||
SLE_pin(LOW);
|
||||
|
|
@ -57,10 +60,8 @@ void CIO::process()
|
|||
|
||||
// Switch off the transmitter if needed
|
||||
if (m_txBuffer.getData() == 0U && m_tx) {
|
||||
DEB_pin(LOW);
|
||||
setRX();
|
||||
m_tx = false;
|
||||
DEB_pin(LOW);
|
||||
}
|
||||
|
||||
if (m_rxBuffer.getData() >= 1U) {
|
||||
|
|
@ -85,14 +86,19 @@ void CIO::interrupt()
|
|||
return;
|
||||
|
||||
if(m_tx) {
|
||||
DEB_pin(HIGH);
|
||||
|
||||
m_txBuffer.get(bit);
|
||||
|
||||
#if defined(BIDIR_DATA_PIN)
|
||||
if(bit)
|
||||
RXD_pin_write(HIGH);
|
||||
else
|
||||
RXD_pin_write(LOW);
|
||||
#else
|
||||
if(bit)
|
||||
TXD_pin(HIGH);
|
||||
else
|
||||
TXD_pin(LOW);
|
||||
#endif
|
||||
|
||||
} else {
|
||||
if(RXD_pin())
|
||||
|
|
|
|||
7
IO.h
7
IO.h
|
|
@ -46,6 +46,9 @@ public:
|
|||
void SDATA_pin(bool on);
|
||||
void SLE_pin(bool on);
|
||||
bool RXD_pin();
|
||||
#if defined(BIDIR_DATA_PIN)
|
||||
void RXD_pin_write(bool on);
|
||||
#endif
|
||||
void TXD_pin(bool on);
|
||||
void PTT_pin(bool on);
|
||||
void LED_pin(bool on);
|
||||
|
|
@ -57,6 +60,10 @@ public:
|
|||
void COS_pin(bool on);
|
||||
void interrupt(void);
|
||||
|
||||
#if defined(BIDIR_DATA_PIN)
|
||||
void Data_dir_out(bool dir);
|
||||
#endif
|
||||
|
||||
// IO API
|
||||
void write(uint8_t* data, uint16_t length);
|
||||
uint16_t getSpace() const;
|
||||
|
|
|
|||
|
|
@ -32,7 +32,7 @@
|
|||
#define PIN_SLE PB8
|
||||
#define PIN_RXD PB4
|
||||
#define PIN_TXD PB3
|
||||
#define PIN_TXRX_CLK PA15
|
||||
#define PIN_CLKOUT PA15
|
||||
#define PIN_LED PC13
|
||||
#define PIN_DEB PB9
|
||||
#define PIN_DSTAR_LED PB12
|
||||
|
|
@ -51,7 +51,7 @@
|
|||
#define PIN_SLE 6
|
||||
#define PIN_RXD 7
|
||||
#define PIN_TXD 8
|
||||
#define PIN_TXRX_CLK 2 // 4 in Arduino Zero Pro
|
||||
#define PIN_CLKOUT 2 // 4 in Arduino Zero Pro
|
||||
#define PIN_LED 13
|
||||
#define PIN_DEB 11
|
||||
#define PIN_DSTAR_LED 14
|
||||
|
|
@ -92,8 +92,7 @@ void CIO::Init()
|
|||
pinMode(PIN_SDATA, OUTPUT);
|
||||
pinMode(PIN_SLE, OUTPUT);
|
||||
pinMode(PIN_RXD, INPUT);
|
||||
pinMode(PIN_TXD, OUTPUT);
|
||||
pinMode(PIN_TXRX_CLK, INPUT);
|
||||
pinMode(PIN_CLKOUT, INPUT);
|
||||
pinMode(PIN_LED, OUTPUT);
|
||||
pinMode(PIN_DEB, OUTPUT);
|
||||
pinMode(PIN_DSTAR_LED, OUTPUT);
|
||||
|
|
@ -103,17 +102,47 @@ void CIO::Init()
|
|||
pinMode(PIN_PTT_LED, OUTPUT);
|
||||
pinMode(PIN_COS_LED, OUTPUT);
|
||||
|
||||
#if defined(BIDIR_DATA_PIN)
|
||||
pinMode(PIN_TXD, INPUT);
|
||||
#else
|
||||
pinMode(PIN_TXD, OUTPUT);
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
void CIO::startInt()
|
||||
{
|
||||
#if defined(BIDIR_DATA_PIN)
|
||||
|
||||
// TXD pin is TxRxCLK of ADF7021, standard TX/RX data interface
|
||||
#if defined (__STM32F1__)
|
||||
attachInterrupt(PIN_TXRX_CLK, EXT_IRQHandler, RISING);
|
||||
attachInterrupt(PIN_TXD, EXT_IRQHandler, RISING);
|
||||
#else
|
||||
attachInterrupt(digitalPinToInterrupt(PIN_TXRX_CLK), EXT_IRQHandler, RISING);
|
||||
attachInterrupt(digitalPinToInterrupt(PIN_TXD), EXT_IRQHandler, RISING);
|
||||
#endif
|
||||
|
||||
#else
|
||||
|
||||
#if defined (__STM32F1__)
|
||||
attachInterrupt(PIN_CLKOUT, EXT_IRQHandler, RISING);
|
||||
#else
|
||||
attachInterrupt(digitalPinToInterrupt(PIN_CLKOUT), EXT_IRQHandler, RISING);
|
||||
#endif
|
||||
|
||||
#endif
|
||||
}
|
||||
|
||||
#if defined(BIDIR_DATA_PIN)
|
||||
// RXD pin is bidirectional in standard interfaces
|
||||
void CIO::Data_dir_out(bool dir)
|
||||
{
|
||||
if(dir)
|
||||
pinMode(PIN_RXD, OUTPUT);
|
||||
else
|
||||
pinMode(PIN_RXD, INPUT);
|
||||
}
|
||||
#endif
|
||||
|
||||
void CIO::SCLK_pin(bool on)
|
||||
{
|
||||
digitalWrite(PIN_SCLK, on ? HIGH : LOW);
|
||||
|
|
@ -134,6 +163,13 @@ bool CIO::RXD_pin()
|
|||
return digitalRead(PIN_RXD) == HIGH;
|
||||
}
|
||||
|
||||
#if defined(BIDIR_DATA_PIN)
|
||||
void CIO::RXD_pin_write(bool on)
|
||||
{
|
||||
digitalWrite(PIN_RXD, on ? HIGH : LOW);
|
||||
}
|
||||
#endif
|
||||
|
||||
void CIO::TXD_pin(bool on)
|
||||
{
|
||||
digitalWrite(PIN_TXD, on ? HIGH : LOW);
|
||||
|
|
|
|||
80
IOSTM.cpp
80
IOSTM.cpp
|
|
@ -39,13 +39,18 @@
|
|||
#define PIN_RXD GPIO_Pin_4
|
||||
#define PORT_RXD GPIOB
|
||||
|
||||
// TXD used in SPI Data mode of ADF7021
|
||||
// TXD is TxRxCLK of ADF7021, standard TX/RX data interface
|
||||
#define PIN_TXD GPIO_Pin_3
|
||||
#define PORT_TXD GPIOB
|
||||
#define PIN_TXD_INT GPIO_PinSource3
|
||||
#define PORT_TXD_INT GPIO_PortSourceGPIOB
|
||||
|
||||
#define PIN_TXRX_CLK GPIO_Pin_15
|
||||
#define PORT_TXRX_CLK GPIOA
|
||||
#define PIN_TXRX_CLK_INT GPIO_PinSource15
|
||||
#define PORT_TXRX_CLK_INT GPIO_PortSourceGPIOA
|
||||
// CLKOUT used in SPI Data mode of ADF7021
|
||||
#define PIN_CLKOUT GPIO_Pin_15
|
||||
#define PORT_CLKOUT GPIOA
|
||||
#define PIN_CLKOUT_INT GPIO_PinSource15
|
||||
#define PORT_CLKOUT_INT GPIO_PortSourceGPIOA
|
||||
|
||||
#define PIN_LED GPIO_Pin_13
|
||||
#define PORT_LED GPIOC
|
||||
|
|
@ -72,12 +77,21 @@
|
|||
#define PORT_COS_LED GPIOB
|
||||
|
||||
extern "C" {
|
||||
#if defined(BIDIR_DATA_PIN)
|
||||
void EXTI3_IRQHandler(void) {
|
||||
if(EXTI_GetITStatus(EXTI_Line3)!=RESET) {
|
||||
io.interrupt();
|
||||
EXTI_ClearITPendingBit(EXTI_Line3);
|
||||
}
|
||||
}
|
||||
#else
|
||||
void EXTI15_10_IRQHandler(void) {
|
||||
if(EXTI_GetITStatus(EXTI_Line15)!=RESET) {
|
||||
io.interrupt();
|
||||
EXTI_ClearITPendingBit(EXTI_Line15);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
|
|
@ -101,7 +115,11 @@ static inline void delay_us(uint32_t us) {
|
|||
}
|
||||
|
||||
void CIO::delay_rx() {
|
||||
#if defined(BIDIR_DATA_PIN)
|
||||
delay_us(290);
|
||||
#else
|
||||
delay_us(340);
|
||||
#endif
|
||||
}
|
||||
|
||||
void CIO::dlybit(void)
|
||||
|
|
@ -163,16 +181,23 @@ void CIO::Init()
|
|||
GPIO_Init(PORT_RXD, &GPIO_InitStruct);
|
||||
|
||||
// Pin TXD
|
||||
// TXD is TxRxCLK of ADF7021, standard TX/RX data interface
|
||||
GPIO_InitStruct.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
GPIO_InitStruct.GPIO_Pin = PIN_TXD;
|
||||
#if defined(BIDIR_DATA_PIN)
|
||||
GPIO_InitStruct.GPIO_Mode = GPIO_Mode_IN_FLOATING;
|
||||
#else
|
||||
GPIO_InitStruct.GPIO_Mode = GPIO_Mode_Out_PP;
|
||||
#endif
|
||||
GPIO_Init(PORT_TXD, &GPIO_InitStruct);
|
||||
|
||||
// Pin TXRX_CLK
|
||||
#if !defined(BIDIR_DATA_PIN)
|
||||
GPIO_InitStruct.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
GPIO_InitStruct.GPIO_Pin = PIN_TXRX_CLK;
|
||||
GPIO_InitStruct.GPIO_Pin = PIN_CLKOUT;
|
||||
GPIO_InitStruct.GPIO_Mode = GPIO_Mode_IN_FLOATING;
|
||||
GPIO_Init(PORT_TXRX_CLK, &GPIO_InitStruct);
|
||||
GPIO_Init(PORT_CLKOUT, &GPIO_InitStruct);
|
||||
#endif
|
||||
|
||||
// Pin LED
|
||||
GPIO_InitStruct.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
|
|
@ -222,30 +247,60 @@ void CIO::Init()
|
|||
GPIO_InitStruct.GPIO_Mode = GPIO_Mode_Out_PP;
|
||||
GPIO_Init(PORT_COS_LED, &GPIO_InitStruct);
|
||||
|
||||
#if defined(BIDIR_DATA_PIN)
|
||||
// Connect EXTI3 Line
|
||||
GPIO_EXTILineConfig(PORT_TXD_INT, PIN_TXD_INT);
|
||||
// Configure EXTI3 line
|
||||
EXTI_InitStructure.EXTI_Line = EXTI_Line3;
|
||||
#else
|
||||
// Connect EXTI15 Line
|
||||
GPIO_EXTILineConfig(PORT_TXRX_CLK_INT, PIN_TXRX_CLK_INT);
|
||||
|
||||
GPIO_EXTILineConfig(PORT_CLKOUT_INT, PIN_CLKOUT_INT);
|
||||
// Configure EXTI15 line
|
||||
EXTI_InitStructure.EXTI_Line = EXTI_Line15;
|
||||
#endif
|
||||
|
||||
EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt;
|
||||
EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising;
|
||||
EXTI_InitStructure.EXTI_LineCmd = ENABLE;
|
||||
EXTI_Init(&EXTI_InitStructure);
|
||||
|
||||
}
|
||||
|
||||
void CIO::startInt()
|
||||
{
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
|
||||
#if defined(BIDIR_DATA_PIN)
|
||||
// Enable and set EXTI3 Interrupt
|
||||
NVIC_InitStructure.NVIC_IRQChannel = EXTI3_IRQn;
|
||||
#else
|
||||
// Enable and set EXTI15 Interrupt
|
||||
NVIC_InitStructure.NVIC_IRQChannel = EXTI15_10_IRQn;
|
||||
#endif
|
||||
|
||||
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
|
||||
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
|
||||
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
||||
NVIC_Init(&NVIC_InitStructure);
|
||||
}
|
||||
|
||||
#if defined(BIDIR_DATA_PIN)
|
||||
// RXD pin is bidirectional in standard interfaces
|
||||
void CIO::Data_dir_out(bool dir)
|
||||
{
|
||||
GPIO_InitTypeDef GPIO_InitStruct;
|
||||
|
||||
GPIO_InitStruct.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
GPIO_InitStruct.GPIO_Pin = PIN_RXD;
|
||||
|
||||
if(dir)
|
||||
GPIO_InitStruct.GPIO_Mode = GPIO_Mode_Out_PP;
|
||||
else
|
||||
GPIO_InitStruct.GPIO_Mode = GPIO_Mode_IN_FLOATING;
|
||||
|
||||
GPIO_Init(PORT_RXD, &GPIO_InitStruct);
|
||||
}
|
||||
#endif
|
||||
|
||||
void CIO::SCLK_pin(bool on)
|
||||
{
|
||||
GPIO_WriteBit(PORT_SCLK, PIN_SCLK, on ? Bit_SET : Bit_RESET);
|
||||
|
|
@ -266,6 +321,13 @@ bool CIO::RXD_pin()
|
|||
return GPIO_ReadInputDataBit(PORT_RXD, PIN_RXD) == Bit_SET;
|
||||
}
|
||||
|
||||
#if defined(BIDIR_DATA_PIN)
|
||||
void CIO::RXD_pin_write(bool on)
|
||||
{
|
||||
GPIO_WriteBit(PORT_RXD, PIN_RXD, on ? Bit_SET : Bit_RESET);
|
||||
}
|
||||
#endif
|
||||
|
||||
void CIO::TXD_pin(bool on)
|
||||
{
|
||||
GPIO_WriteBit(PORT_TXD, PIN_TXD, on ? Bit_SET : Bit_RESET);
|
||||
|
|
|
|||
Loading…
Reference in a new issue