mirror of
https://github.com/opentx/opentx.git
synced 2025-07-26 17:55:19 +03:00
Add debug read, Add PXX preamble, Add Taranis no_pulses drivers
This commit is contained in:
parent
ea1a07dbfa
commit
53cbfd5d8f
4 changed files with 260 additions and 1 deletions
137
src/debug.cpp
137
src/debug.cpp
|
@ -74,14 +74,148 @@ void dump(unsigned char *data, unsigned int size)
|
|||
debugPuts("\n\r");
|
||||
}
|
||||
|
||||
uint32_t Mem_address ;
|
||||
uint32_t Next_mem_address ;
|
||||
uint32_t Memaddmode ;
|
||||
|
||||
void txmit( uint8_t chr )
|
||||
{
|
||||
debugTxFifo.push( chr) ;
|
||||
}
|
||||
|
||||
void crlf()
|
||||
{
|
||||
txmit( 13 ) ;
|
||||
txmit( 10 ) ;
|
||||
}
|
||||
|
||||
// Send a single 4 bit value to the RS232 port as a hex digit
|
||||
void hex_digit_send( unsigned char c )
|
||||
{
|
||||
c &= 0x0F ;
|
||||
if ( c > 9 )
|
||||
{
|
||||
c += 7 ;
|
||||
}
|
||||
c += '0' ;
|
||||
txmit( c ) ;
|
||||
}
|
||||
|
||||
// Send the 8 bit value to the RS232 port as 2 hex digits
|
||||
void p2hex( unsigned char c )
|
||||
{
|
||||
// asm("swap %c") ;
|
||||
hex_digit_send( c >> 4 ) ;
|
||||
// asm("swap %c") ;
|
||||
hex_digit_send( c ) ;
|
||||
}
|
||||
|
||||
// Send the 16 bit value to the RS232 port as 4 hex digits
|
||||
void p4hex( uint16_t value )
|
||||
{
|
||||
p2hex( value >> 8 ) ;
|
||||
p2hex( value ) ;
|
||||
}
|
||||
|
||||
// Send the 32 bit value to the RS232 port as 8 hex digits
|
||||
void p8hex( uint32_t value )
|
||||
{
|
||||
p4hex( value >> 16 ) ;
|
||||
p4hex( value ) ;
|
||||
}
|
||||
|
||||
|
||||
static void dispw_256( register uint32_t address, register uint32_t lines )
|
||||
{
|
||||
register uint32_t i ;
|
||||
register uint32_t j ;
|
||||
address &= 0xFFFFFFFC ;
|
||||
for ( i = 0 ; i < lines ; i += 1 )
|
||||
{
|
||||
p8hex( address ) ;
|
||||
for ( j = 0 ; j < 4 ; j += 1 )
|
||||
{
|
||||
txmit(' ') ;
|
||||
p8hex( *( (uint32_t *)address ) ) ;
|
||||
address += 4 ;
|
||||
}
|
||||
crlf() ;
|
||||
}
|
||||
}
|
||||
|
||||
void debugTask(void* pdata)
|
||||
{
|
||||
uint8_t rxchar ;
|
||||
crlf() ;
|
||||
dispw_256( (uint32_t)USART3, 4 ) ;
|
||||
|
||||
for (;;) {
|
||||
while (!debugRxFifo.pop(rxchar))
|
||||
|
||||
|
||||
while ( (USART3->SR & USART_SR_RXNE) == 0 )
|
||||
CoTickDelay(5); // 10ms
|
||||
|
||||
rxchar = USART3->DR ;
|
||||
|
||||
if ( Memaddmode )
|
||||
{
|
||||
if ( ( rxchar >= 'a' ) && ( rxchar <= 'f' ) )
|
||||
{
|
||||
rxchar -= 0x20 ; // toupper!
|
||||
}
|
||||
if ( ( ( rxchar >= '0' ) && ( rxchar <= '9' ) ) || ( ( rxchar >= 'A' ) && ( rxchar <= 'F' ) ) )
|
||||
{
|
||||
txmit( rxchar ) ;
|
||||
rxchar -= '0' ;
|
||||
if ( rxchar > 9 )
|
||||
{
|
||||
rxchar -= 7 ;
|
||||
}
|
||||
Mem_address <<= 4 ;
|
||||
Mem_address |= rxchar ;
|
||||
}
|
||||
else if ( rxchar == 13 )
|
||||
{
|
||||
crlf() ;
|
||||
if ( Mem_address == 0 )
|
||||
{
|
||||
Mem_address = Next_mem_address ;
|
||||
}
|
||||
dispw_256( Mem_address, 4 ) ;
|
||||
Next_mem_address = Mem_address + 64 ;
|
||||
Memaddmode = 0 ;
|
||||
}
|
||||
else if ( rxchar == 8 )
|
||||
{
|
||||
txmit( rxchar ) ;
|
||||
txmit( rxchar ) ;
|
||||
txmit( rxchar ) ;
|
||||
Mem_address >>= 4 ;
|
||||
}
|
||||
else if ( rxchar == 27 )
|
||||
{
|
||||
crlf() ;
|
||||
Memaddmode = 0 ;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
if ( rxchar == '?' )
|
||||
{
|
||||
Memaddmode = 1 ;
|
||||
Mem_address = 0 ;
|
||||
txmit( '>' ) ;
|
||||
}
|
||||
|
||||
if ( rxchar == 'm' )
|
||||
{
|
||||
crlf() ;
|
||||
p8hex( (uint32_t) &g_model.moduleData[0] ) ;
|
||||
txmit( ' ' ) ;
|
||||
p8hex( (uint32_t) &g_model.moduleData[1] ) ;
|
||||
crlf() ;
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -92,4 +226,5 @@ void debugTx(void)
|
|||
if (debugTxFifo.pop(txchar))
|
||||
debugPutc(txchar);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -57,6 +57,11 @@ OS_TID btTaskId;
|
|||
OS_STK btStack[BT_STACK_SIZE];
|
||||
#endif
|
||||
|
||||
#if defined(PCBTARANIS) && defined(DEBUG)
|
||||
OS_TID debugTaskId;
|
||||
OS_STK debugStack[DEBUG_STACK_SIZE];
|
||||
#endif
|
||||
|
||||
#if defined(PCBSKY9X) && defined(DEBUG)
|
||||
OS_TID debugTaskId;
|
||||
OS_STK debugStack[DEBUG_STACK_SIZE];
|
||||
|
@ -4359,6 +4364,10 @@ int main(void)
|
|||
debugTaskId = CoCreateTaskEx(debugTask, NULL, 10, &debugStack[DEBUG_STACK_SIZE-1], DEBUG_STACK_SIZE, 1, false);
|
||||
#endif
|
||||
|
||||
#if defined(PCBTARANIS) && defined(DEBUG)
|
||||
debugTaskId = CoCreateTaskEx(debugTask, NULL, 10, &debugStack[DEBUG_STACK_SIZE-1], DEBUG_STACK_SIZE, 1, false);
|
||||
#endif
|
||||
|
||||
#if defined(BLUETOOTH)
|
||||
btTaskId = CoCreateTask(btTask, NULL, 15, &btStack[BT_STACK_SIZE-1], BT_STACK_SIZE);
|
||||
#endif
|
||||
|
|
|
@ -148,6 +148,11 @@ void setupPulsesPXX(unsigned int port)
|
|||
PcmCrc[port] = 0;
|
||||
PcmOnesCount[port] = 0;
|
||||
|
||||
/* preamble */
|
||||
putPcmPart(0, port);
|
||||
putPcmPart(0, port);
|
||||
putPcmPart(0, port);
|
||||
putPcmPart(0, port);
|
||||
/* Sync */
|
||||
putPcmHead(port);
|
||||
|
||||
|
|
|
@ -52,6 +52,10 @@ static void init_pa7_pxx( void ) ;
|
|||
static void disable_pa7_pxx( void ) ;
|
||||
static void init_pa7_ppm( void ) ;
|
||||
static void disable_pa7_ppm( void ) ;
|
||||
static void init_pa10_none( void ) ;
|
||||
static void disable_pa10_none( void ) ;
|
||||
static void init_pa7_none()
|
||||
static void disable_pa7_none()
|
||||
|
||||
void init_pxx(uint32_t port)
|
||||
{
|
||||
|
@ -85,6 +89,112 @@ void disable_ppm(uint32_t port)
|
|||
disable_pa7_ppm();
|
||||
}
|
||||
|
||||
void init_no_pulses(uint32_t port)
|
||||
{
|
||||
if (port == INTERNAL_MODULE)
|
||||
init_pa10_none();
|
||||
else
|
||||
init_pa7_none();
|
||||
}
|
||||
|
||||
void disable_no_pulses(uint32_t port)
|
||||
{
|
||||
if (port == INTERNAL_MODULE)
|
||||
disable_pa10_none();
|
||||
else
|
||||
disable_pa7_none();
|
||||
}
|
||||
|
||||
static void init_pa10_none()
|
||||
{
|
||||
INTERNAL_RF_OFF();
|
||||
|
||||
// Timer1, channel 3
|
||||
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIO_INTPPM, ENABLE);
|
||||
|
||||
GPIO_InitStructure.GPIO_Pin = PIN_INTPPM_OUT;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT ;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_100MHz;
|
||||
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
|
||||
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
|
||||
GPIO_Init(GPIO_INTPPM, &GPIO_InitStructure);
|
||||
|
||||
GPIO_SetBits(GPIO_INTPPM,PIN_INTPPM_OUT) ; // Set high
|
||||
|
||||
RCC->APB2ENR |= RCC_APB2ENR_TIM1EN ; // Enable clock
|
||||
|
||||
TIM1->CR1 &= ~TIM_CR1_CEN ;
|
||||
TIM1->ARR = 36000 ; // 18mS
|
||||
TIM1->CCR2 = 32000 ; // Update time
|
||||
TIM1->PSC = (PERI2_FREQUENCY * TIMER_MULT_APB2) / 2000000 - 1 ; // 0.5uS from 30MHz
|
||||
|
||||
TIM1->CCER = TIM_CCER_CC3E ;
|
||||
|
||||
TIM1->CCMR2 = 0 ;
|
||||
TIM1->EGR = 1 ; // Restart
|
||||
|
||||
TIM1->CCMR2 = TIM_CCMR2_OC3M_1 | TIM_CCMR2_OC3M_0 ; // Toggle CC1 o/p
|
||||
TIM1->SR &= ~TIM_SR_CC2IF ; // Clear flag
|
||||
TIM1->DIER |= TIM_DIER_CC2IE ; // Enable this interrupt
|
||||
TIM1->CR1 |= TIM_CR1_CEN ;
|
||||
NVIC_EnableIRQ(TIM1_CC_IRQn) ;
|
||||
}
|
||||
|
||||
static void disable_pa10_none()
|
||||
{
|
||||
NVIC_DisableIRQ(TIM1_CC_IRQn) ;
|
||||
TIM1->DIER &= ~TIM_DIER_CC2IE ;
|
||||
TIM1->CR1 &= ~TIM_CR1_CEN ;
|
||||
INTERNAL_RF_OFF();
|
||||
}
|
||||
|
||||
static void init_pa7_none()
|
||||
{
|
||||
EXTERNAL_RF_ON();
|
||||
|
||||
// Timer8
|
||||
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIO_EXTPPM, ENABLE);
|
||||
|
||||
GPIO_InitStructure.GPIO_Pin = PIN_EXTPPM_OUT;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT ;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_100MHz;
|
||||
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
|
||||
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
|
||||
GPIO_Init(GPIO_EXTPPM, &GPIO_InitStructure);
|
||||
|
||||
GPIO_SetBits(GPIO_EXTPPM,PIN_EXTPPM_OUT) ; // Set high
|
||||
|
||||
RCC->APB2ENR |= RCC_APB2ENR_TIM8EN ; // Enable clock
|
||||
|
||||
TIM1->CR1 &= ~TIM_CR1_CEN ;
|
||||
TIM8->ARR = 36000 ; // 18mS
|
||||
TIM8->CCR2 = 32000 ; // Update time
|
||||
TIM8->PSC = (PERI2_FREQUENCY * TIMER_MULT_APB2) / 2000000 - 1 ; // 0.5uS from 30MHz
|
||||
|
||||
TIM8->CCMR2 = 0 ;
|
||||
TIM8->EGR = 1 ; // Restart
|
||||
|
||||
TIM8->CCMR2 = TIM_CCMR2_OC3M_1 | TIM_CCMR2_OC3M_0 ; // Toggle CC1 o/p
|
||||
TIM8->SR &= ~TIM_SR_CC2IF ; // Clear flag
|
||||
TIM8->DIER |= TIM_DIER_CC2IE ; // Enable this interrupt
|
||||
TIM8->CR1 |= TIM_CR1_CEN ;
|
||||
NVIC_EnableIRQ(TIM8_CC_IRQn) ;
|
||||
}
|
||||
|
||||
static void disable_pa7_none()
|
||||
{
|
||||
NVIC_DisableIRQ(TIM8_CC_IRQn) ;
|
||||
TIM8->DIER &= ~TIM_DIER_CC2IE ;
|
||||
TIM8->CR1 &= ~TIM_CR1_CEN ;
|
||||
EXTERNAL_RF_OFF();
|
||||
}
|
||||
|
||||
|
||||
|
||||
static void init_pa10_pxx()
|
||||
{
|
||||
INTERNAL_RF_ON();
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue