Attiny816 external interrupt issue - interrupt

recently working on tachometer using attiny816.
Basically using 5 inputs to sense pulses from hall sensors (using interrupts to sense rising edge).
During the test when I use simple transistor key to simulate hall sensor (give rectangular wave with different frequency) I've notice that after a time microcontroller slows down(yes, working like in slow motion). Sometimes it takes few minutes, sometimes several hours.
To find the problem I created simple program to toggle led when interrupt is triggered and change speed value. Just to mention, on sample code using internal 32k clock, when changed to 20MHz, it was working correctly for several hours (much longer than on 32k).
Tried program on Attiny816 and Attiny826, same problem on both.
Any ideas what can cause the problem?
Test code below.
On each input there is a different time between interrupts (different signal frequency)
PB5 - interrupt every 120ms
PB4 - interrupt every 60ms
PB3 - interrupt every 40ms
PB2 - interrupt every 30ms
PB1 - interrupt every 24ms
/*
* Attiny816 VQFN TeST.c
*
* Created: 01/11/2022 10:11:41
* Author :
*/
#define F_CPU 32768UL
#include <avr/io.h>
#include <stdlib.h>
#include <stdio.h>
#include <string.h>
#include <avr/interrupt.h>
#include <avr/wdt.h>
#include <util/delay.h>
#include <avr/eeprom.h>
#include <avr/pgmspace.h>
#define USART0_BAUD_RATE(BAUD_RATE) ((float)(F_CPU * 64 / (16 * (float)BAUD_RATE)) + 0.5)
void USART0_init(void);
void USART0_sendChar(char c);
void USART0_sendString(char *str);
int USART0_printChar(char c, FILE *stream);
void reset_screen(void);
FILE USART_stream = FDEV_SETUP_STREAM(USART0_printChar, NULL, _FDEV_SETUP_WRIT);
uint16_t speed_read(uint8_t wejscie_TACHO);
int main(void)
{
CPU_CCP = CCP_IOREG_gc;
CLKCTRL_MCLKCTRLA = CLKCTRL_CLKSEL_OSCULP32K_gc; /*32.768 kHz */
CPU_CCP = CCP_IOREG_gc;
CLKCTRL_MCLKCTRLB = 0 << CLKCTRL_PEN_bp; /* prescaler DISABLED */
/* --- ALARM LED'S --- */
PORTC.DIRSET = PIN3_bm; // F1 ALARM LED
PORTC.DIRSET = PIN2_bm; // F2 ALARM LED
PORTC.DIRSET = PIN1_bm; // F3 ALARM LED
PORTC.DIRSET = PIN0_bm; // F4 ALARM LED
PORTB.DIRSET = PIN0_bm; // F5 ALARM LED
/* --- USART --- */
USART0_init();
printf( "%cc", 27 );
/* --- TACHO --- */
PORTB.PIN5CTRL = PORT_ISC_INTDISABLE_gc; //TACHO_1_DIS
PORTB.PIN4CTRL = PORT_ISC_INTDISABLE_gc; //TACHO_2_DIS
PORTB.PIN3CTRL = PORT_ISC_INTDISABLE_gc; //TACHO_3_DIS
PORTB.PIN2CTRL = PORT_ISC_INTDISABLE_gc; //TACHO_4_DIS
PORTB.PIN1CTRL = PORT_ISC_INTDISABLE_gc; //TACHO_5_DIS
sei();
/* Replace with your application code */
while (1)
{
printf("\n\r Speed 1 - %u[rpm]", speed_read(1));
printf("\n\r Speed 2 - %u[rpm]", speed_read(2));
printf("\n\r Speed 3 - %u[rpm]", speed_read(3));
printf("\n\r Speed 4 - %u[rpm]", speed_read(4));
printf("\n\r Speed 5 - %u[rpm]", speed_read(5));
USART0_sendString("\n\r");
}
}
ISR( PORTB_PORT_vect )
{
switch ( PORTB_INTFLAGS )
{
case (32): // TACHO_1 - PB5 (2^(5-1) = 32)
////tacho_now[1] = TCA0.SINGLE.CNT;
PORTB.INTFLAGS |= PORT_INT5_bm; /* clear interrupt flag */
break;
case (16): // TACHO_2 - PB4
////tacho_now[2] = TCA0.SINGLE.CNT; // tacho_cnt;
PORTB.INTFLAGS |= PORT_INT4_bm; /* clear interrupt flag */
break;
case (8): // TACHO_3 - PB3
////tacho_now[3] = TCA0.SINGLE.CNT;
PORTB.INTFLAGS |= PORT_INT3_bm; /* clear interrupt flag */
break;
case (4): // TACHO_4 - PB2
//tacho_now[4] = TCA0.SINGLE.CNT;
PORTB.INTFLAGS |= PORT_INT2_bm; /* clear interrupt flag */
break;
case (2): // TACHO_5 - PB1
////tacho_now[5] = TCA0.SINGLE.CNT;
PORTB.INTFLAGS |= PORT_INT1_bm; /* clear interrupt flag */
break;
default:
break;
}
}
void USART0_init(void)
{
PORTMUX.CTRLB = PORTMUX_USART0_ALTERNATE_gc;
PORTA.DIRSET = PIN1_bm; // PA1 - TXD jako wyjscie
USART0.BAUD = (uint16_t)USART0_BAUD_RATE( 1200 ); // set the Baud Rate
USART0.CTRLB |= USART_TXEN_bm; // enable the Transmitter
// Set frame format
USART0.CTRLC = USART_CMODE_ASYNCHRONOUS_gc // Asynchronous Mode
| USART_CHSIZE_8BIT_gc // Character size: 8 bit
| USART_PMODE_DISABLED_gc // No Parity
| USART_SBMODE_1BIT_gc; // 1 stop bit
stdout = &USART_stream;
_delay_ms(250);
}
void USART0_sendChar(char c)
{
while ( !(USART0.STATUS & USART_DREIF_bm) )
{
; // do nothing
}
USART0.TXDATAL = c;
}
void USART0_sendString(char *str)
{
for(size_t i = 0; i < strlen(str); i++)
{
USART0_sendChar(str[i]);
}
}
int USART0_printChar(char c, FILE *stream)
{
USART0_sendChar(c);
return 0;
}
uint16_t speed_read(uint8_t wejscie_TACHO)
{
uint32_t speed = 0;
/* --- disable all TACHO input --- */
PORTB.PIN5CTRL = PORT_ISC_INTDISABLE_gc; //TACHO_1_DIS
PORTB.PIN4CTRL = PORT_ISC_INTDISABLE_gc; //TACHO_2_DIS
PORTB.PIN3CTRL = PORT_ISC_INTDISABLE_gc; //TACHO_3_DIS
PORTB.PIN2CTRL = PORT_ISC_INTDISABLE_gc; //TACHO_4_DIS
PORTB.PIN1CTRL = PORT_ISC_INTDISABLE_gc; //TACHO_5_DIS
//_delay_ms(100);
/* --- enable [wejscie_TACHO] only --- */
switch ( wejscie_TACHO )
{
case (1):
speed = 500;
PORTC.OUTTGL = PIN3_bm;// _delay_ms(200);
PORTB.PIN5CTRL = PORT_ISC_RISING_gc;
break;
case (2):
speed = 1000;
PORTC.OUTTGL = PIN2_bm; //_delay_ms(200);
PORTB.PIN4CTRL = PORT_ISC_RISING_gc;
break;
case (3):
speed = 1500;
PORTC.OUTTGL = PIN1_bm; //_delay_ms(200);
PORTB.PIN3CTRL = PORT_ISC_RISING_gc;
break;
case (4):
speed = 2000;
PORTC.OUTTGL = PIN0_bm; //_delay_ms(200);
PORTB.PIN2CTRL = PORT_ISC_RISING_gc;
break;
case (5):
speed = 2500;
PORTB.OUTTGL = PIN0_bm; //_delay_ms(200);
PORTB.PIN1CTRL = PORT_ISC_RISING_gc;
break;
default:
break;
}
_delay_ms(250);
return speed;
}
I've tried different chips, tested power supply and the input signal waves, all look like it should be.
It looks like the microcontroller after while get lost in the interrupts routine.

Found the problem,
The interrupt handler doesn't take into consideration if 2 or more pins are triggering interrupt at the same time.

Related

STM32F3 Dual ADC with interleaved mode

I'm trying to achieve 10MSPS as documented in STM32F30x ADC modes and application under the section Dual interleaved mode.
Firstly, i tried to use single DMA. I configured the DMA1 Channel1 to read from ADC1&2 Common data register. It worked but i could only achieve a sample rate of 8.47MSPS. Beyond that limit, ADC1 starts to overrun.
(Register ADC1_2->CCR: MULT=0x07, MDMA=0x02, DELAY=0x04) Considering the DMA reading the common data register after the slave adc ends its conversion, the problem seems reasonable at high sample rates.
So i decided to use 2 DMAs. One for each ADC:
DMA1 Channel1 copies from ADC1->DR to SRAM
DMA2 Channel1 copies from ADC2->DR to SRAM
(Register ADC1_2->CCR: MULT=0x07, MDMA=0x00, DELAY=0x04)
This configuration also worked but again up to 8MSPS. Above that rate, ADC2 starts to overrun. I cannot understand why ADC2 overruns. I expected that this setup would work.
When i run ADC1 & ADC2 in independent mode with DMA configuration above, everything seems to work fine. No overruns, both ADC samples at 5.1MSPS but independently.
One question: What happens when both ADCs run in independent mode and triggered from the same source (e.g. TIM2) but ADC1 is triggered at the rising edge and ADC2 is triggered at the falling edge of the clock ? Would it work? This is the next thing i will try.
The MCU i work with is STM32F303CB.
ADC sampling times were 1.5 Cycles.
Any advice will be appreciated.
Edit: I have provided a minimal sample code that runs on STM32F3 Discovery with an 8 MHz Crystal. Program directly jumps to main()
// main.c
#include "stm32f30x.h"
#define DUALDMA
void sysinit();
void clockconfig();
void delay(int d);
void timerinit();
void adcinit();
void dmainit();
void dualdmainit();
int main(){
sysinit();
clockconfig();
timerinit();
#ifdef DUALDMA
dualdmainit();
#else
dmainit();
#endif
adcinit();
RCC->AHBENR |= RCC_AHBENR_GPIOEEN; // GPIOE enable
RCC->AHBENR |= RCC_AHBENR_GPIOAEN; // GPIOA enable
GPIOE->MODER = 0x55555555; // GPIOE -> output
GPIOA->MODER |= 0x0000FFFF;// GPIOA -> analog
// Reset SRAM memory area
for(int i = 0;i<1024*4;i+=4){
*((uint32_t*)(0x20000800+i)) = 0;
}
// Blink LEDs
while(1){
GPIOE->ODR = 0xFFFF;
delay(1000);
GPIOE->ODR = 0x00FF;
delay(1000);
}
}
void delay(int d){
// Dummy delay
int l = d*1000;
for(int i = 0;i<l;i++);
}
void sysinit(){
//STM32F303 reset state
/* Reset the RCC clock configuration to the default reset state ------------*/
/* Set HSION bit */
RCC->CR |= 0x00000001U;
/* Reset CFGR register */
RCC->CFGR &= 0xF87FC00CU;
/* Reset HSEON, CSSON and PLLON bits */
RCC->CR &= 0xFEF6FFFFU;
/* Reset HSEBYP bit */
RCC->CR &= 0xFFFBFFFFU;
/* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE bits */
RCC->CFGR &= 0xFF80FFFFU;
/* Reset PREDIV1[3:0] bits */
RCC->CFGR2 &= 0xFFFFFFF0U;
/* Reset USARTSW[1:0], I2CSW and TIMs bits */
RCC->CFGR3 &= 0xFF00FCCCU;
/* Disable all interrupts */
RCC->CIR = 0x00000000U;
SCB->VTOR = 0x08000000; /* Vector Table Relocation in Internal FLASH */
}
void adcinit(){
RCC->AHBENR |= RCC_AHBENR_ADC12EN; // Enable ADC clock
RCC->CFGR2 |= RCC_CFGR2_ADCPRE12_4;// ADC clock prescaler = 1
ADC1->CFGR |= ADC_CFGR_EXTEN_0; // Trigger on rising edge
ADC1->CFGR |= ADC_CFGR_EXTSEL_3 | ADC_CFGR_EXTSEL_1; // TIM1 TRGO2
ADC1->SQR1 |= ADC_SQR1_SQ1_0 ; // ch 1
ADC1->CFGR |= ADC_CFGR_OVRMOD; // Stop on overrun
ADC1->CFGR |= ADC_CFGR_DMAEN; // DMA enable
ADC1->CR &= ~(ADC_CR_ADVREGEN_1 | ADC_CR_ADVREGEN_0); // Enable VREG
ADC1->CR |= ADC_CR_ADVREGEN_0;
ADC1->CR |= ADC_CR_ADEN;
while( (ADC1->ISR & ADC_ISR_ADRD) == 0 );
ADC2->SQR1 |= ADC_SQR1_SQ1_0 ; // ch 1
ADC2->CFGR |= ADC_CFGR_DMAEN;
ADC2->CR &= ~(ADC_CR_ADVREGEN_1 | ADC_CR_ADVREGEN_0);
ADC2->CR |= ADC_CR_ADVREGEN_0;
ADC2->CR |= ADC_CR_ADEN;
while( (ADC1->ISR & ADC_ISR_ADRD) == 0 );
ADC1_2->CCR |= ADC12_CCR_DELAY_2 ; // Delay = 4, 5 Cycles
#ifndef DUALDMA
ADC1_2->CCR |= ADC12_CCR_MDMA_1; // If single DMA is selected, configure MDMA bits for 12 bits
#endif
ADC1_2->CCR |= ADC12_CCR_MULTI_2 | ADC12_CCR_MULTI_1 | ADC12_CCR_MULTI_0; // Interleaved mode
}
void dmainit(){
// DMA config for Single DMA, 32 bits
RCC->AHBENR |= RCC_AHBENR_DMA1EN;
DMA1_Channel1->CPAR = (uint32_t)&ADC1_2->CDR;
DMA1_Channel1->CMAR = 0x20000800;
DMA1_Channel1->CNDTR = 1024;
DMA1_Channel1->CCR = DMA_CCR_EN | DMA_CCR_MINC | DMA_CCR_MSIZE_1 | DMA_CCR_PSIZE_1;
//DMA1_Channel1->CCR = DMA_CCR_EN | DMA_CCR_MINC ;
}
void dualdmainit(){
// DMA config for DUAL DMA, 16bits
RCC->AHBENR |= RCC_AHBENR_DMA1EN; // DMA1 Enable
RCC->AHBENR |= RCC_AHBENR_DMA2EN; // DMA2 Enable
DMA1_Channel1->CPAR = (uint32_t)&ADC1->DR;
DMA1_Channel1->CMAR = 0x20000800;
DMA1_Channel1->CNDTR = 1024;
DMA1_Channel1->CCR = DMA_CCR_EN | DMA_CCR_MINC | DMA_CCR_MSIZE_0 | DMA_CCR_PSIZE_0;
DMA2_Channel1->CPAR = (uint32_t)&ADC2->DR;
DMA2_Channel1->CMAR = 0x20000800+1024*2;
DMA2_Channel1->CNDTR = 1024;
DMA2_Channel1->CCR = DMA_CCR_EN | DMA_CCR_MINC | DMA_CCR_MSIZE_0 | DMA_CCR_PSIZE_0;
}
void timerinit(){
RCC->APB2ENR |= RCC_APB2ENR_TIM1EN; // Enable TIM1
TIM1->CR2 |= TIM_CR2_MMS2_1; // Update event selected as TRGO2
TIM1->PSC = 0;
TIM1->ARR = 0x0d; // 5 MHz (72 MHz / 14 )
TIM1->CR1 |= TIM_CR1_CEN;
}
void clockconfig(){
// External oscillator (HSE): 8MHz
RCC->CR |= RCC_CR_HSEON; // Enable HSE
while( (RCC->CR & RCC_CR_HSERDY) == 0 );
RCC->CFGR |= RCC_CFGR_PLLMULL9; // PLL MUL = x9
RCC->CFGR |= RCC_CFGR_PPRE1_DIV2; // APB1 Prescaler = 2
RCC->CFGR |= RCC_CFGR_PLLSRC; // PLL source = HSE
FLASH->ACR |= FLASH_ACR_LATENCY_1; // Two wait states
RCC->CR |= RCC_CR_PLLON; // Enable and wait PLL
while( (RCC->CR & RCC_CR_PLLRDY) == 0 );
RCC->CFGR |= RCC_CFGR_SW_PLL; // Select PLL as system clock
}
Scatter file:
LR_IROM1 0x08000000 0x00020000 { ; load region size_region
ER_IROM1 0x08000000 0x00020000 { ; load address = execution address
*.o (RESET, +First)
*(InRoot$$Sections)
.ANY (+RO)
}
RW_IRAM2 0x10000000 0x00000200 { ; RW data
.ANY (+RW +ZI)
}
}
You cant do it this way. You need to use only one DMA channel and both samples are transmitted in one 32 bit DMA transaction.
In 6 bits mode I have archived more than 18MSPS
I do not know how to program it using HAL as I personally do only the bare register approach
There is a hardware problem as well (read the errata) and sometimes in >8bit modes the transfer does not work properly.
For dual DMA you need to:
Prevent any core accesses to the SRAM memory by placing the stack and the variables (except the ADC buffers) in the CCM RAM or suspending any core activity by entering the sleep mode.

Input Capture mapping using PPS

I am trying to configure input capture module (IC1) on dsPIC33EP32MC204 to use it for duty cycle measurement. As input I would like to use RP35 pin. To test the correctness of the configuration I set up an experiment: I connected a pulse generator with 1Hz PWM pulses and set up the input capture to capture every rising edge. I reckoned that these rising edges will trigger the input capture interrupt and each call of the interrupt will cause the LED to blink. Unfortunatelly it is not working. I would be grateful if someone could tell me where is the problem. The code:
void Init_InputCapture(void)
{
IC1CON1bits.ICSIDL = 0;
IC1CON1bits.ICTSEL = 0b111; // Peripheral clock (FP) is the clock source of the ICx
IC1CON1bits.ICI = 0b00; //
IC1CON1bits.ICM = 0b011; //Capture mode every edge rising
IC1CON2bits.ICTRIG = 0; // = Input source used to trigger the input capture timer (Trigger mode)
IC1CON2bits.SYNCSEL = 0b00000; //IC1 module synchronizes or triggers ICx
IC1CON2bits.IC32 = 0; // 16 bit mode only
// Enable Capture Interrupt And Timer2
IPC0bits.IC1IP = 1; // Setup IC1 interrupt priority level
IFS0bits.IC1IF = 0; // Clear IC1 Interrupt Status Flag
IEC0bits.IC1IE = 1; // Enable IC1 interrupt
}
The interrupt:
void __attribute__((__interrupt__, no_auto_psv)) _IC1Interrupt(void)
{
LATBbits.LATB9 = ~LATBbits.LATB9;
IFS0bits.IC1IF = 0;
}
And the related code from the main():
__builtin_write_OSCCONL(OSCCON & ~(1<<6));
RPINR7 = 0x23; ; // IC1 mapped to RP35
__builtin_write_OSCCONL(OSCCON | (1<<6));
During the setup I followed the instuctions from the family reference manual.
The code you have posted could be more complete. For dsPIC controllers it is essential to show exactly how all of the configuration bits are set and how the system clock is initialized.
This is your code corrected with the minimum required setup code:
/*
* file: main.c
* target: dsPIC33EP32MC204
* IDE: MPLABX v4.05
* Compiler: XC16 v1.35
*
* Description:
* Use Input Capture 1 module to catch a 1Hz pulse on GPIO RP35 and toggle LED on RB9.
*
*/
#pragma config ICS = PGD2 // ICD Communication Channel Select bits (Communicate on PGEC2 and PGED2)
#pragma config JTAGEN = OFF // JTAG Enable bit (JTAG is disabled)
#pragma config ALTI2C1 = OFF // Alternate I2C1 pins (I2C1 mapped to SDA1/SCL1 pins)
#pragma config ALTI2C2 = OFF // Alternate I2C2 pins (I2C2 mapped to SDA2/SCL2 pins)
#pragma config WDTWIN = WIN25 // Watchdog Window Select bits (WDT Window is 25% of WDT period)
#pragma config WDTPOST = PS32768 // Watchdog Timer Postscaler bits (1:32,768)
#pragma config WDTPRE = PR128 // Watchdog Timer Prescaler bit (1:128)
#pragma config PLLKEN = ON // PLL Lock Enable bit (Clock switch to PLL source will wait until the PLL lock signal is valid.)
#pragma config WINDIS = OFF // Watchdog Timer Window Enable bit (Watchdog Timer in Non-Window mode)
#pragma config FWDTEN = OFF // Watchdog Timer Enable bit (Watchdog timer enabled/disabled by user software)
#pragma config POSCMD = NONE // Primary Oscillator Mode Select bits (Primary Oscillator disabled)
#pragma config OSCIOFNC = OFF // OSC2 Pin Function bit (OSC2 is clock output)
#pragma config IOL1WAY = OFF // Peripheral pin select configuration (Allow multiple reconfigurations)
#pragma config FCKSM = CSECMD // Clock Switching Mode bits (Clock switching is enabled,Fail-safe Clock Monitor is disabled)
#pragma config FNOSC = FRC // Oscillator Source Selection (Internal Fast RC (FRC))
#pragma config PWMLOCK = ON // PWM Lock Enable bit (Certain PWM registers may only be written after key sequence)
#pragma config IESO = OFF // Two-speed Oscillator Start-up Enable bit (Start up with user-selected oscillator source)
#pragma config GWRP = OFF // General Segment Write-Protect bit (General Segment may be written)
#pragma config GCP = OFF // General Segment Code-Protect bit (General Segment Code protect is Disabled)
#include <xc.h>
/* Setup the clock to run at about 60 MIPS */
#define FOSC (7372800L) /* nominal fast RC frequency */
#define PLL_N1 (2L) /* PLLPRE CLKDIV<4:0> range 2 to 33 */
#define PLL_M (65L) /* PLLDIV PLLFBD<8:0> range 2 to 513 */
#define PLL_N2 (2L) /* PLLPOST CLKDIV<7:6> range 2, 4 or 8 */
#define FSYS (FOSC*PLL_M/(PLL_N1*PLL_N2))
#define FCYC (FSYS/2L)
/*
* Global constant data
*/
const unsigned long gInstructionCyclesPerSecond = FCYC;
/*
* Initialize this PIC
*/
void PIC_Init( void )
{
unsigned int ClockSwitchTimeout;
/*
** Disable all interrupt sources
*/
__builtin_disi(0x3FFF); /* disable interrupts for 16383 cycles */
IEC0 = 0;
IEC1 = 0;
IEC2 = 0;
IEC3 = 0;
IEC4 = 0;
IEC5 = 0;
IEC6 = 0;
IEC8 = 0;
IEC9 = 0;
__builtin_disi(0x0000); /* enable interrupts */
CLKDIV = 0; /* Disable DOZE mode */
if(!OSCCONbits.CLKLOCK) /* if primary oscillator switching is unlocked */
{
/* Select primary oscillator as FRC */
__builtin_write_OSCCONH(0b000);
/* Request switch primary to new selection */
__builtin_write_OSCCONL(OSCCON | (1 << _OSCCON_OSWEN_POSITION));
/* wait, with timeout, for clock switch to complete */
for(ClockSwitchTimeout=10000; --ClockSwitchTimeout && OSCCONbits.OSWEN;);
/* Configure PLL prescaler, PLL postscaler, PLL divisor */
PLLFBD=PLL_M-2; /* M=65 */
#if PLL_N2==2
CLKDIVbits.PLLPOST=0; /* N2=2 */
#elif PLL_N2==4
CLKDIVbits.PLLPOST=1; /* N2=4 */
#elif PLL_N2==8
CLKDIVbits.PLLPOST=3; /* N2=8 */
#else
#error invalid PLL_N2 paramenter
#endif
CLKDIVbits.PLLPRE=PLL_N1-2; /* N1=2 */
/* Select primary oscillator as FRCPLL */
__builtin_write_OSCCONH(0b001);
/* Request switch primary to new selection */
__builtin_write_OSCCONL(OSCCON | (1 << _OSCCON_OSWEN_POSITION));
/* wait, with timeout, for clock switch to complete */
for(ClockSwitchTimeout=10000; --ClockSwitchTimeout && OSCCONbits.OSWEN;);
/* wait, with timeout, for the PLL to lock */
for(ClockSwitchTimeout=10000; --ClockSwitchTimeout && !OSCCONbits.LOCK;);
/* at this point the system oscillator should be 119.808MHz */
}
/* make all inputs digital I/O */
ANSELA = 0x00;
ANSELB = 0x00;
ANSELC = 0x00;
/* Unlock PPS Registers */
__builtin_write_OSCCONL(OSCCON & ~(_OSCCON_IOLOCK_MASK));
/* map all PPS pins */
RPINR7bits.IC1R = 35; // Select RP35 (RB3/PGED1) as input for IC1
/* Lock PPS Registers */
__builtin_write_OSCCONL(OSCCON | (_OSCCON_IOLOCK_MASK));
}
/*
* Initialize Input Capture 1
*/
void Init_InputCapture( void )
{
IC1CON1bits.ICSIDL = 0;
IC1CON1bits.ICTSEL = 0b111; // Peripheral clock (FP) is the clock source of the ICx
IC1CON1bits.ICI = 0b00; //
IC1CON1bits.ICM = 0b011; //Capture mode every edge rising
IC1CON2bits.ICTRIG = 0; // = Input source used to trigger the input capture timer (Trigger mode)
IC1CON2bits.SYNCSEL = 0b00000; //IC1 module synchronizes or triggers ICx
IC1CON2bits.IC32 = 0; // 16 bit mode only
// Enable Capture Interrupt And Timer2
IPC0bits.IC1IP = 4; // Setup IC1 interrupt priority level
IFS0bits.IC1IF = 0; // Clear IC1 Interrupt Status Flag
IEC0bits.IC1IE = 1; // Enable IC1 interrupt
}
/*
* Interrupt Service Routine for IC1
*/
void __attribute__((__interrupt__, no_auto_psv)) _IC1Interrupt(void)
{
IFS0bits.IC1IF = 0;
LATBbits.LATB9 ^= 1; // toggle LED
}
/*
* Main process loop
*/
int main( void )
{
PIC_Init();
TRISBbits.TRISB9 = 0; // make RB9 an output
LATBbits.LATB9 = 0; // turn off LED
Init_InputCapture();
for(;;)
{
/* process loop */
}
return 0;
}

dsPIC33EP128MC202 UART receiver doesn't work

I wrote the code for UART communication. TX is working fine, but RX is not working. I have searched a lot but found no solution.
I am transmitting character x to PC with time interval, and I am able see the data. But when transmits data pic is not receiving any thing.
Below are pins used for uart
//PGEC1/AN4/C1IN1+/RPI34/RB2 for receiver
RPINR18bits.U1RXR = 34;
//RP36/RB4 for transmitting data
RPOR1bits.RP36R = 1;
I am able transmit data to pc but PIC doesn't receive any charector from pc.
Thanks in advance
Here is my code.
DSPIC33EP128MC202
/*
* File: newmainXC16.c
* Author:
*
* Created on 27 December, 2017, 4:21 PM
*/
// FICD
#pragma config ICS = PGD3 // ICD Communication Channel Select bits (Communicate on PGEC3 and PGED3)
#pragma config JTAGEN = OFF // JTAG Enable bit (JTAG is disabled)
// FPOR
#pragma config ALTI2C1 = OFF // Alternate I2C1 pins (I2C1 mapped to SDA1/SCL1 pins)
#pragma config ALTI2C2 = OFF // Alternate I2C2 pins (I2C2 mapped to SDA2/SCL2 pins)
#pragma config WDTWIN = WIN25 // Watchdog Window Select bits (WDT Window is 25% of WDT period)
// FWDT
#pragma config WDTPOST = PS32768 // Watchdog Timer Postscaler bits (1:32,768)
#pragma config WDTPRE = PR128 // Watchdog Timer Prescaler bit (1:128)
#pragma config PLLKEN = ON // PLL Lock Enable bit (Clock switch to PLL source will wait until the PLL lock signal is valid.)
#pragma config WINDIS = OFF // Watchdog Timer Window Enable bit (Watchdog Timer in Non-Window mode)
#pragma config FWDTEN = OFF // Watchdog Timer Enable bit (Watchdog timer enabled/disabled by user software)
// FOSC
#pragma config POSCMD = NONE // Primary Oscillator Mode Select bits (Primary Oscillator disabled)
#pragma config OSCIOFNC = ON // OSC2 Pin Function bit (OSC2 is clock output)
#pragma config IOL1WAY = ON // Peripheral pin select configuration (Allow only one reconfiguration)
#pragma config FCKSM = CSDCMD // Clock Switching Mode bits (Both Clock switching and Fail-safe Clock Monitor are disabled)
// FOSCSEL
#pragma config FNOSC = FRCPLL // Oscillator Source Selection (Fast RC Oscillator with divide-by-N with PLL module (FRCPLL) )
#pragma config PWMLOCK = ON // PWM Lock Enable bit (Certain PWM registers may only be written after key sequence)
#pragma config IESO = ON // Two-speed Oscillator Start-up Enable bit (Start up device with FRC, then switch to user-selected oscillator source)
// FGS
#pragma config GWRP = OFF // General Segment Write-Protect bit (General Segment may be written)
#pragma config GCP = OFF // General Segment Code-Protect bit (General Segment Code protect is Disabled)
#include "xc.h"
#include <stdint.h>
#include <p33EP128MC202.h>
#define FP 60000000
#define BAUDRATE 115200
#define BRGVAL ((FP/BAUDRATE)/16)-1
#define DELAY_100uS asm volatile ("REPEAT, #5400"); Nop(); // 100uS delay
int main(void)
{
uint8_t c;
int i,j,a,b;
// Configure Oscillator to operate the device at 60Mhz
// Fosc= Fin*M/(N1*N2), Fcy=Fosc/2
// Fosc= 8M*60/(2*2)=120Mhz for 8M input clock == 8*60/4 = 120/2 = 60
CLKDIVbits.PLLPOST=0; // PLLPOST (N1) 0=/2
while(!OSCCONbits.LOCK); // wait for PLL ready
PLLFBD = 58; // M=60
CLKDIVbits.PLLPOST = 0; // N1=2
CLKDIVbits.PLLPRE = 0; // N2=2
OSCTUN = 0; // Tune FRC oscillator, if FRC is used
/*Initialize the Ports */
TRISA = 0x00;
LATA = 0x0000;
PORTA = 0x0000;
ANSELAbits.ANSA1 = 0;
ANSELAbits.ANSA0 = 0;
__builtin_write_OSCCONL(OSCCON & ~(1<<6));
RPINR18bits.U1RXR = 34;
RPOR1bits.RP36R = 1;
__builtin_write_OSCCONL(OSCCON | (1<<6));
U1MODEbits.STSEL = 0;
U1MODEbits.PDSEL = 0;
U1MODEbits.ABAUD = 0;
U1MODEbits.BRGH = 0;
U1BRG = 30;
U1MODEbits.UARTEN = 1;
IEC0bits.U1TXIE = 0;
U1STAbits.UTXEN = 1;
U1STAbits.URXISEL = 0;
DELAY_100uS;
DELAY_100uS;
DELAY_100uS;
U1TXREG = 'X';
char ReceivedChar;
while(1){
//If data is received send data to TX
if(U1STAbits.URXDA == 1) {
ReceivedChar = U1RXREG + 2;
U1TXREG = 10;
U1TXREG = 13;
}
for(i=0;i<1000;i++){
a = a + 1;
for(j=0;j<2000;j++){
b = b + 1;
}
}
//LED Blink code for programme check
if(c == 0){
c = 1;
}else{
c = 0;
}
LATAbits.LATA0 = c;
LATAbits.LATA1 = c;
U1TXREG = 'x';
U1TXREG = 10;
U1TXREG = 13;
}
}
void __attribute__((interrupt, no_auto_psv)) _U1TXInterrupt( void )
{
IFS0bits.U1TXIF = 0; // Clear TX Interrupt flag
}
void __attribute__((interrupt, no_auto_psv)) _U1RXInterrupt( void )
{
IFS0bits.U1RXIF = 0; // Clear RX Interrupt flag
//cntr++;
U1TXREG='a';
U1TXREG = 10;
U1TXREG = 13;
}
I looked into the code, It works fine for me.
Please check the connection with your peripherals and their pins. If there is an extra connection to that pin remove it and try it again.
RB2 should be an an Input.
TRISB = 0x04;

Delayed uart command execution

I'm writing a small embedded program, where I send some commands over uart to the atmega328p chip. The commands start with the character $ and end with the character # (so I know when to perform the parsing). Upon receiving the command I parse it and turn the device on (COMMAND:TURN_ON_I1) or off (COMMAND:TURN_OFF_I1). The application currently looks like this:
// ------- Defines -------- //
#define F_CPU 8000000UL
#include <avr/io.h>
#include <util/delay.h>
#include <avr/power.h>
#include <stdio.h>
#include <string.h>
#include "pinDefines.h"
#include "USART.h"
#define RECEIVE_BUFFER_SIZE 100
// Control output value
#define output_low(port,pin) port &= ~(1<<pin)
#define output_high(port,pin) port |= (1<<pin)
// Set pin mode (input or output)
#define set_input(portdir,pin) portdir &= ~(1<<pin)
#define set_output(portdir,pin) portdir |= (1<<pin)
// The DDRD port contains only two pins:
#define REL_BTN_SIM_2 PD6 // PD6 = REL_BTN_SIM_2
void initUSART(void) { /* requires BAUD */
UBRR0H = UBRRH_VALUE; /* defined in setbaud.h */
UBRR0L = UBRRL_VALUE;
#if USE_2X
UCSR0A |= (1 << U2X0);
#else
UCSR0A &= ~(1 << U2X0);
#endif
/* Enable USART transmitter/receiver */
UCSR0B = (1 << TXEN0) | (1 << RXEN0);
UCSR0C = (1 << UCSZ01) | (1 << UCSZ00); /* 8 data bits, 1 stop bit */
}
void printString(const char myString[]) {
uint8_t i = 0;
while (myString[i]) {
transmitByte(myString[i]);
i++;
}
}
uint8_t receiveByte(void) {
loop_until_bit_is_set(UCSR0A, RXC0); /* Wait for incoming data */
return UDR0; /* return register value */
}
void transmitByte(uint8_t data) {
/* Wait for empty transmit buffer */
loop_until_bit_is_set(UCSR0A, UDRE0);
UDR0 = data; /* send data */
}
int main(void) {
//$COMMAND:TURN_ON_I1#
//$COMMAND:TURN_OFF_I1#
char s[RECEIVE_BUFFER_SIZE];
char readSerialCharacter;
// -------- Inits --------- //
DDRB = 0b00000111;
DDRC = 0b00001000;
DDRD = 0b11000000;
initUSART();
// ------ Event loop ------ //
while (1) {
printString("Waiting for the start of string (char $).\r\n");
do { } while ( receiveByte() != '$'); // Wait for start of string.
// Fill the array until the end of transmission is received
int i=0;
do {
// If nearing end of buffer, don't fill the buffer and exit the loop
if(i<RECEIVE_BUFFER_SIZE-1){
readSerialCharacter = receiveByte();
s[i++] = readSerialCharacter;
}else
break;
} while (readSerialCharacter != '#'); // Wait for end of string.
s[i] ='\0'; // Terminate the string
printString("The whole received command:\r\n");
printString(s);
printString("\r\n");
// Other commands (temperature, relay control)
// REL_BTN_SIM_2
else if(strstr(s, "COMMAND:TURN_ON_I1") != NULL)
{
printString("Will set I1 on!");
output_high(PORTD, REL_BTN_SIM_2);
}
else if(strstr(s, "COMMAND:TURN_OFF_I1") != NULL)
{
printString("Will set I1 off!");
output_low(PORTD, REL_BTN_SIM_2);
}
else
printString("Unknown command.\r\n");
// Clear the buffer
memset(s,'\0', sizeof(s));
}
/* End event loop */
return (0);
}
I noticed that after I send a command around seven or eight times (or more), the serial communication is interrupted or that the command is executed with a delay. I can also see, that the debug strings "Will set I1 off!", "Will set I1 on!" are printed, but the state of the outputs are not changed (or are changed with a delay of a couple of seconds).
I was wondering if someone would know, what I'm doing wrong?
Thanks.
You have a nice definition of set_output(), but you are not using it. So I suspect that you never enabled the output driver. By setting the port register, you just enable the weak pull-up. Maybe that is not strong enough to switch on your relay driver fast. Do you have a capacitor in that driver circuit?

PIC32 UART transmission trouble, no data being transmitted

I am trying to use UART1 on PIC32 to transmit and receive data but there is nothing coming out from that port.
I am using the PIC32 Ethernet kit with 8Mhz crystal.
For the programming in C I am using MPLAB IDE v2.15 and XC32 v 1.32
I don't have scope available right now so I was trying to test with multimeter which is very limited. When I connect the meter to UART1 TX pin and can see that once the initU1 routine is executed the pin goes from 0V to 3.3V which seems to be working but when the bits are supposed to be transmitted I don't see anything on the LCD (LK204-25), I also had the multimeter connected and don't see any change in voltage, it also does not show any frequency. The baud rate is set to 9600.
The code I am using is shown below, please let me know what should be changed to get it to work.
/*
* File: main.c
* Author: Acer
*
* Created on August 27, 2014, 11:57 PM
*/
#include <stdio.h>
#include <stdlib.h>
//#include <p32xxxx.h>
#include <proc/p32mx795f512l.h>
#include <plib.h>
/*
*
*/
#define CTS1 _RD14
#define RTS1 _RD15
#define TRTS1 TRISDbits.TRISD15
#define BRATE1 368 //2083 //9600 #80MHz, BREGH=1
#define U_ENABLE1 0x8008 //BREGH=1, 1 stop, no parity
#define U_TX1 0x0400 //Enable TX, Clear all flags
#define CTS2 _RF12
#define RTS2 _RF13
#define TRTS2 TRISFbits.TRISF13
#define BRATE2 2082 //9600 #80MHz, BREGH=1
#define U_ENABLE2 0x8008 //BREGH=1, 1 stop, no parity
#define U_TX2 0x0400 //Enable TX, Clear all flags
char Port1Buffer[100], Port2Buffer[100];
int i1=0, i2=0;
int nextRun1=0, nextRun2=0;
void __attribute__ ((interrupt(ipl1),vector(27)))
U1RXInterruptHandler(void)//UART 1 RX interrupt routine
{
if(mU1RXGetIntFlag())
{
// Clear the RX interrupt Flag
mU1RXClearIntFlag();
// Echo what we just received
//putcUART1(ReadUART1());
Port1Buffer[i1]=ReadUART1();
i1++;
if(i1==100){
i1=0;
nextRun1=1;
}
// Toggle LED to indicate UART activity
mPORTDToggleBits(BIT_0);
}
// We don't care about TX interrupt
if ( mU1TXGetIntFlag() )
{
mU1TXClearIntFlag();
}
}
void __attribute__ ((interrupt(ipl2),vector(41)))
U2RXInterruptHandler(void)//UART 2 RX interrupt routine
{
if(mU2RXGetIntFlag())
{
// Clear the RX interrupt Flag
mU2RXClearIntFlag();
// Echo what we just received
//putcUART2(ReadUART2());
Port2Buffer[i2]=ReadUART2();
i2++;
if(i2==100){
i2=0;
nextRun2=1;
}
// Toggle LED to indicate UART activity
mPORTDToggleBits(BIT_0);
}
// We don't care about TX interrupt
if ( mU2TXGetIntFlag() )
{
mU2TXClearIntFlag();
}
}
void initU1(void)
{
U1BRG = BRATE1; //Initialize baud rate generator
U1MODE = U_ENABLE1; //Initialize UART module
U1STA = U_TX1; //Enable Transmitter
TRTS1 = 0; //Make RTS an output pin
RTS1 = 1; //Set RTS default status (not ready)
//ConfigIntUART1(UART_INT_PR1|UART_RX_INT_EN);
}
void initU2(void)
{
U2BRG = BRATE2; //Initialize baud rate generator
U2MODE = U_ENABLE2; //Initialize UART module
U2STA = U_TX2; //Enable Transmitter
TRTS2 = 0; //Make RTS an output pin
RTS2 = 1; //Set RTS default status (not ready)
ConfigIntUART2(UART_INT_PR2|UART_RX_INT_EN);
}
void putU1(char c)
{
// while(CTS1);
while(U1STAbits.UTXBF);
U1TXREG = c;
}
void putU2(char c)
{
while(CTS2);
while(U2STAbits.UTXBF);
U2TXREG = c;
}
void DelayRoutine(int delint){
int delcount=0;
while(delcount < delint){
delcount++;
}
}
void main(void) {
DelayRoutine(0xFFFF);
// mU1SetIntPriority(1);
// mU2SetIntPriority(2);
INTEnableSystemMultiVectoredInt();
//mU1IntEnable( 1);
//mU2IntEnable( 1);
int y1=0, y2=0;
initU1();
initU2();
// putU1(0x41);
putU1(0xFE);
putU1(0x58);
while(1)
{
if(y1<i1 || nextRun1==1){
putU1(Port1Buffer[y1]);
y1++;
if(y1==100){
y1=0;
nextRun1=0;
}
}
/* if(y2<i2 || nextRun2==1){
putU1(Port2Buffer[y2]);
y2++;
if(y2==100){
y2=0;
nextRun2=0;
}
}
*/ }
//U2CTS=1;
//return (EXIT_SUCCESS);
}
void init_serial_port( U32 ulWantedBaud )
{
unsigned short usBRG;
/* Configure the UART and interrupts. */
usBRG = (unsigned short)(( (float)40000000/ ( (float)16 * (float)ulWantedBaud ) ) - (float)0.5);
OpenUART2( UART_EN, UART_RX_ENABLE | UART_TX_ENABLE | UART_INT_TX | UART_INT_RX_CHAR, usBRG );
ConfigIntUART2( ( configKERNEL_INTERRUPT_PRIORITY + 1 ) | UART_INT_SUB_PR0 | UART_RX_INT_EN );
U2STAbits.UTXISEL = 0x00;
}
Just replace my "2" with a 1 and that is my exact init sequence for my UART on a PIC32MX745F512L
ulWantedBaud is my desired baud rate (usually 115200, but sometimes 9600 depending on my settings)
I can't post my interrupt handler b/c it is way too involved, but use the serial port API's they are much less complex. Also, I would suggest a simple Logic Analyzer like this one (Used on the TTL side of course).
Side Note: If you use the API's they take care of the TRIS and LAT for you.
Edit: Adding Pragmas
#pragma config DEBUG = OFF // Background Debugger disabled
#pragma config FPLLMUL = MUL_20 // PLL Multiplier: Multiply by 20
#pragma config FPLLIDIV = DIV_2 // PLL Input Divider: Divide by 2
#pragma config FPLLODIV = DIV_1 // PLL Output Divider: Divide by 1
#pragma config FWDTEN = OFF // WD timer: OFF
#pragma config POSCMOD = HS // Primary Oscillator Mode: High Speed xtal
#pragma config FNOSC = PRIPLL // Oscillator Selection: Primary oscillator w/ PLL
#pragma config FPBDIV = DIV_1 // Peripheral Bus Clock: Divide by 1 //Note: Application FPBDIV = DIV_2
#pragma config BWP = OFF // Boot write protect: OFF
#pragma config ICESEL = ICS_PGx2 // ICE pins configured on PGx2, Boot write protect OFF.
#pragma config WDTPS = PS1 // Watchdog Timer Postscale
#pragma config CP = OFF
#pragma config PWP = OFF
#pragma config UPLLEN = ON
#pragma config UPLLIDIV = DIV_2 // USB PLL Input Divider
#pragma config FSRSSEL = PRIORITY_7
#pragma config FMIIEN = OFF
#pragma config FVBUSONIO = OFF // VBUSON is controlled by the port
#pragma config FETHIO = ON // external PHY in RMII/alternate configuration
#pragma config FUSBIDIO = OFF // USB ID controlled by PORT function