STM8 UART polling receive is mangles - uart

I'm trying to connect to an STM8 using uart. The STM seems to transmit data OK, but what it receives seems to be mostly junk, and often seems to receive 2 bytes at once. Here's the code:
#include "../stm8.h"
//
// Setup the system clock to run at 16MHz using the internal oscillator.
//
void InitialiseSystemClock()
{
CLK_ICKR = 0; // Reset the Internal Clock Register.
CLK_ICKR |= CLK_ICKR_HSIEN ; // Enable the HSI.
CLK_ECKR = 0; // Disable the external clock.
while ((CLK_ICKR & CLK_ICKR_HSIRDY) == 0); // Wait for the HSI to be ready for use.
CLK_CKDIVR = 0; // Ensure the clocks are running at full speed.
CLK_PCKENR1 = 0xff; // Enable all peripheral clocks.
CLK_PCKENR2 = 0xff; // Ditto.
CLK_CCOR = 0; // Turn off CCO.
CLK_HSITRIMR = 0; // Turn off any HSIU trimming.
CLK_SWIMCCR = 0; // Set SWIM to run at clock / 2.
CLK_SWR = 0xe1; // Use HSI as the clock source.
CLK_SWCR = 0; // Reset the clock switch control register.
CLK_SWCR |= CLK_SWCR_SWEN; // Enable switching.
while ((CLK_SWCR & CLK_SWCR_SWBSY) != 0); // Pause while the clock switch is busy.
}
//
// Setup the UART to run at 115200 baud, no parity, one stop bit, 8 data bits.
//
// Important: This relies upon the system clock being set to run at 16 MHz.
//
void init_uart()
{
//
// Clear the Idle Line Detected bit in the status register by a read
// to the UART1_SR register followed by a Read to the UART1_DR register.
//
//unsigned char tmp = UART1_SR;
//tmp = UART1_DR;
//UART1_SR = 0xC0; // mcarter set to default value
//
// Reset the UART registers to the reset values.
//
UART1_CR1 = 0;
UART1_CR2 = 0;
UART1_CR4 = 0;
UART1_CR3 = 0;
UART1_CR5 = 0;
UART1_GTR = 0;
UART1_PSCR = 0;
//
// Now setup the port to 115200,n,8,1.
//
// clear certain bits
UART1_CR1 &= ~UART1_CR1_M ; // 8 Data bits.
UART1_CR1 &= ~UART1_CR1_PCEN; // Disable parity
// stop bits
UART1_CR3 &= 0b11001111; // unmask the stop bit to default (1 stop bit)
//UART1_CR3 |= 0b00100000; // two stop bits
//UART1_CR3 |= 0b00110000; // 1.5 stop bits
//UART1_CR3 &= ~UART1_CR3_STOP; // 1 stop bit.
#if 1 //115200 baud
//UART1_BRR2 = 0x0a; // given in original example
UART1_BRR2 = 0x0b; // Set the baud rate registers to 115200 baud
UART1_BRR1 = 0x08; // based upon a 16 MHz system clock.
#else // 9600 baud, but seems to be worse than 115200
UART1_BRR2 = 0x03;
UART1_BRR1 = 0x69;
#endif
//
// Disable the transmitter and receiver.
//
//UART1_CR2_TEN = 0; // Disable transmit.
//UART1_CR2_REN = 0; // Disable receive.
//
// Set the clock polarity, lock phase and last bit clock pulse.
//
UART1_CR3 |= UART1_CR3_CPOL;
UART1_CR3 |= UART1_CR3_CPHA;
//UART1_CR3 |= UART1_CR3_LBCL; // this seems to cause problems
UART1_CR2 |= UART1_CR2_TEN; // enable transmit
UART1_CR2 |= UART1_CR2_REN; // enable receive
UART1_CR3 |= UART1_CR3_CLKEN; // unable uart clock
}
char uart_getc()
{
while((UART1_SR & UART1_SR_RXNE)==0); // Block until char rec'd
//char c = UART1_DR;
//return c;
return UART1_DR;
}
void uart_putc(char c)
{
while((UART1_SR & UART1_SR_TXE)==0); // Wait for transmission complete
UART1_DR = c; // transmit char
}
void UARTPrintf(char *message)
{
char *ch = message;
while (*ch)
uart_putc(*ch++);
}
void main()
{
disable_interrupts();
InitialiseSystemClock();
init_uart();
enable_interrupts();
UARTPrintf("Uart example: you type, I echo\n\r");
while (1)
{
//continue;
char c = uart_getc();
uart_putc(c);
//UARTPrintf("Hello from my microcontroller....\n\r");
//for (long counter = 0; counter < 2500000; counter++);
}
}
Relevant declaration headers are:
#define UART1_SR *(uchar*)(0x5230)
#define UART1_DR *(uchar*)(0x5231)
#define UART1_BRR1 *(uchar*)(0x5232)
#define UART1_BRR2 *(uchar*)(0x5233)
#define UART1_CR1 *(uchar*)(0x5234)
#define UART1_CR2 *(uchar*)(0x5235)
#define UART1_CR3 *(uchar*)(0x5236)
#define UART1_CR4 *(uchar*)(0x5237)
#define UART1_CR5 *(uchar*)(0x5238)
#define UART1_GTR *(uchar*)(0x5239)
#define UART1_PSCR *(uchar*)(0x523A)
#define UART1_CR1_M (1<<4)
#define UART1_CR1_PCEN (1<<2)
#define UART1_CR2_TEN (1<<3)
#define UART1_CR2_REN (1<<2)
#define UART1_CR3_STOP 4
#define UART1_CR3_CPOL (1<<2)
#define UART1_CR3_CPHA (1<<1)
#define UART1_CR3_LBCL (1<<0)
#define UART1_CR3_CLKEN (1<<3)
#define UART1_SR_TXE (1<<7)
#define UART1_SR_TC (1<<6)
#define UART1_SR_RXNE (1<<5)
I'm not really sure about stop bits, and all that. It's just "regular" serial communication.
I found that if I uncommented the line
//UART1_CR3 |= UART1_CR3_LBCL; // this seems to cause problems
then the stm8 prints out a continuous stream of junk. But with it commented out, the mcu seems to correctly know that there has been a transmission. There doesn't seem to be any pattern as to what it sees, though.

Hmm. The offending line seems to be
UART1_CR3 |= UART1_CR3_CLKEN;
It's purpose seem to be to "enable the SCLK pin". I don't really understand what's going on here, but according to a pinout diagram, one of the purposes of pin PD4 is UART1_CK. So you can attach a UART clock to the STM8 and this enables it?? And thereby causes problems if a clock isn't attached. It doesn't make that much sense, really; I didn't know uarts could have external clocks.
Anyway, commenting out the line seems to have fixed things.

Related

Distance measurement using Ultrasonic and ATMEGA32

I'm working on a Distance measurement program using an AVR microcontroller. I use a 16x2 LCD and an ultrasonic sensor along with ATMEGA32A. I wrote a code to display the distance from the Ultrasonic HC-SR04 on the LCD screen, but it gives me false readings, it increases the distance when the object is very near and vice versa. I just want an accurate reading.
Ultrasonic datasheet
ATMEGA32A Datasheet
#include <avr/io.h>
#include <avr/interrupt.h>
#include <MrLcd/MrLCDmega32.h>
#define F_CPU 1000000
#include <util/delay.h>
#include <stdlib.h>
#define Trigger_pin PD0 /* Trigger pin */
static volatile int pulse = 0;
static volatile int i = 0;
int main(void)
{
Initialise();
DDRD = 0b11111011;
_delay_ms(50);
GICR |= 1<<INT0;
MCUCR |= 1<<ISC00;
int16_t count_a = 0;
char show_a[16];
sei();
while(1)
{
PORTD |= (1<<Trigger_pin);
_delay_us(10);
PORTD &= ~(1<<Trigger_pin);
count_a = pulse/58;
Send_A_String("Distance Sensor");
GoToMrLCDLocation(1,2);
Send_A_String("Distance=");
itoa(count_a,show_a,10);
Send_A_String(show_a);
Send_A_String(" ");
GoToMrLCDLocation(13,2);
Send_A_String("cm");
GoToMrLCDLocation(1,1);
}
}
ISR(INT0_vect)
{
if(i == 1)
{
TCCR1B = 0;
pulse = TCNT1;
TCNT1 = 0;
i = 0;
}
if(i==0)
{
TCCR1B |= 1<<CS10;
i = 1;
}
}
I tried to change the trigger pin definition and define it in the code itself but still no progress.
Update: I changed a bit more in the code but I'm getting hex values when the distance is more than 9, for example, 10 is being displayed as 1e.
This is for initialise function
void Initialise(void)
{
DataDir_MrLCDsControl|=1<<LightSwitch|1<<ReadWrite|1<<BipolarMood; //these information will go towards the LCD
_delay_ms(15); // Wait for the LCD to start
Send_A_Command(0x01); // to clear the screen
_delay_ms(2);
Send_A_Command(0x38); // TO tell LCD about 8 data lines
_delay_us(50);
Send_A_Command(0b00001110); //Some cursor command
_delay_us(50);
}
You are sending pulses at a very rapid rate (determined solely by the display update time), and they are asynchronous to the time/counter reset. You have no idea which pulse triggered the interrupt and it did not start at the same time as the timer.
I would suggest that you reset the counter at the start of the pulse, and capture the counter value on interrupt. When the time has exceeded the maximum range, send a new pulse:
First define some constants:
#define PULSES_PER_CMx100 (F_CPU * 100 / 68600)
#define MAX_RANGE_CM 300
#define MAX_RANGE_COUNT ((MAX_RANGE_CM * PULSES_PER_CMx100) / 100)
Then your measure/display loop might look like:
pulse = 1 ; // dummy start
GICR &= ~(1<<INT0) ; // Disable INT0
for(;;)
{
// Ready for new measurement?...
if( pulse != 0 )
{
// Send pulse and reset timer
PORTD |= (1<<Trigger_pin) ;
pulse = 0 ;
TCNT1 = 0 ;
_delay_us(10);
PORTD &= ~(1<<Trigger_pin) ;
// Wait for echo pulse interrupt...
GIFR |= 1<<INTF0; // Clear INT0 pending flag
GICR |= 1<<INT0 ; // Enable INT0
}
else // When measurement available...
{
int distance_cm = pulse * 100 / PULSES_PER_CMx100 ;
// display distance
...
}
// If out of range, timeout, send a new pulse
if( TCNT1 > MAX_RANGE_COUNT )
{
// Force a new pulse to be triggered
pulse = 1 ;
}
}
And the ISR:
ISR(INT0_vect)
{
pulse = TCNT1; // Capture time on interrupt
GICR &= ~(1<<INT0) ; // Disable further interrupts
}
Now bear in mind that that method will take measurements as fast as possible and since you are displaying them for human reading, that is rather unnecessary. You might simply put a delay in the loop - making the pulse timeout unnecessary, or better you could take the mean of multiple measurements to get a more robust measurement, or use a moving average window, with outlier rejection.

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.

atmega 328p interrupt and timer setup [C/C++]

I am trying to set up one interrupt and one counter/timer. The interrupt is external, reading low logic from pin. Timer should increment every 100 us and add up to count variable.
I've set up the interrupt, which is working fine however, after setting up a timer, neither interrupt nor timer works. The code is such:
volatile boolean allowCount = false, timerFlag = false;
volatile unsigned int counter;
boolean pulseLow = false;
void setup(){
Serial.begin(9600);
// initialize external pin interrupt.
PCICR = 0b00000010; // 1. PCIE1: Pin Change Interrupt Enable 1
EICRA |= bit (ISC10); // set wanted flags (low logic level causes interrupt)
PCMSK1 = 0b00010000; // Enable Pin Change Interrupt for A4
// TODO Interrupt settings not working together
// initialize Timer1
cli(); // disable global interrupts
TCCR1A = 0; // set entire TCCR1A register to 0
TCCR1B = 0; // same for TCCR1B
// set compare match register to desired timer count:
OCR1A = 0x18;
// turn on CTC mode:
TCCR1B |= (1 << WGM12);
// Set CS10 and CS12 bits for 64 prescaler:
TCCR1B |= (1 << CS10);
TCCR1B |= (1 << CS11);
// enable timer compare interrupt:
TIMSK1 |= (1 << OCIE1A);
}
void loop(){
if (allowCount == true)
{ timer100_uS();
if (counter > 50 && pulseLow == false){
DDRC |= (1 << DDC3 ); // sets bit DDC3 to 1 within register DDRC
//set pin 3(A3) ouput as sourcing Vcc(HIGH)
PORTC |= (1 << PORTC3);
timerReset();
pulseLow = true;
}
if (pulseLow == true){
timer100_uS();
if (counter >= 500){
//set pin3 of port C to LOW (A3);
PORTC &= ~(1 << PORTC3);
pulseLow = false
timerReset();
}
}
// external pin interrupt
ISR(PCINT1_vect){
if (allowCount == false)
allowCount = true;
}
// timer/counter interrupt
ISR (TIMER1_COMPA_vect)
{
if (timerFlag == true){
counter++;
}
}
void timer_100uS(void){
timerFlag = true;
cli();
}
void timerReset(void){
sei();
timerFlag = false;
counter = 0;
}
Value of OCR0A is calculated to be 24 (0x18) with prescaler 64 and 16 MHz processor based on this formula:
OCRn = [ (clock_speed / Prescaler_value) * Desired_time_in_Seconds ] - 1
How to set up different interrupts so that they don't overlap eachother ?
Or better yet, is it possible to set up timer so that it does not use interrupt ?
Thanks for reading !
As I can see, you are using ATMega328 with Arduino libraries. Your problem is that Arduino library internally uses Timer 1 for its internal purposes. Therefore if you add your own interrupt handler for Timer 1, you override Arduino's interrupt handler for Timer 1 which breaks the library.
If you want to stay with Arduino library, use the library also to control the timer: Arduino Timer1
Thank you for answers #old_timer, #klasyc.
Quite late, but I solved it by using timer0 instead of timer1 with following settings in setup:
// initialize external pin interrupt.
PCICR = 0b00000010; // 1. PCIE1: Pin Change Interrupt Enable 1
EICRA |= bit (ISC10); // set wanted flags (falling edge causes interrupt)
PCMSK1 = 0b00001000; // Enable Pin Change Interrupt for A3
TCCR0B = 0;
TCCR0A = 0;
//set CTC mode
TCCR0A = ( 1 << WGM01 );
// set OCR0A value for 1 us counter (OCRxn = (freq/prescaler)*desired_value)-1
OCR0A = 15;
// set compare match counter
TIMSK0 |= (1 << OCIE0A);
//set prescaler
TCCR0B |= ( 1 << CS00);
and outside the loop:
ISR(TIMER0_COMPA_vect){
counter++;
}

PIC32MX795F512H UART communication to RS232

I am currently working for the first time with a PIC microcontroller. In the code I specified exactly which PIC, compiler, etc I am using. Maybe this is of help.
I am trying to set up UART communication on the PIC32 and send a hex code like 0x41 for example to a terminal on my computer through RS232. To convert the signal from the PIC UART to RS232 levels I am using a MAX232EPE.
At the moment I am running into the problem that when I send 0x41 for example from the PIC32 to the terminal or vice versa, the received data doesn't match. I think this being caused by a mistake in my baud rate settings, but I am not sure. Could someone please look over my code and see if someone can see a problem? Did I forget to define something? Did I define something wrong? Did I mis calculate the baud rate?
P.S. I know the data being received doesn't match the data send because i checked in the "watches" in debug mode in mplab and when I echo the data send from the terminal to the PIC32 back to the terminal it doesn't match either.
The Delay and interrupt code can be ignored, they are working as expected, so I really believe the problem has to do with the initial setting of the PIC/buad rate.
I hope this is clear enough, any help is very much appreciated
Thanks,
See code below
/*
The configuration below and in void UART1_Init should set up the UART correctly.
I want to achieve a buadrate of 9600. My external Crystal is 8MHz. So:
FPLLIDIV=2, FPLLMUL=20, FPLLODIV=1, FPBDIV=2, FNOSC=PRIPLL, BRGH = 0, and U1BRG = 259.
This should give me the desired baudrate of 9600.
- ((8MHz / 2) * 20)/2) = 40MHz PBclk.
- U1BRG = (PBclk/(16*Buad rate))-1 so 259
- 16*Buad rate because BRGH = 0
PIC32MX795F512H
MPLAB X IDE V3.26
XC32 Compiler
PICKit3
*/
#include <stdio.h>
#include <stdlib.h>
#include <xc.h>
#include <plib.h>
// Give useful names to pins
#define LED1_TRIS TRISDbits.TRISD6
#define LED1 LATDbits.LATD6
#define UART1TX_TRIS TRISDbits.TRISD3
#define UART1RX_TRIS TRISDbits.TRISD2
#define FOSC 8000000 // Crystal frequency = 8 MHz
#define SYS_FREQ (80000000UL) // SYSCLK is 80 MHz
#define GetSystemClock() (FOSC) // For delay
#pragma config FPLLIDIV=DIV_2 // PLL Input Divider Value (Divide by 2)
#pragma config FPLLMUL=MUL_20 // Phase-Locked Loop (PPL) muiltiplier, multiplier of 20
#pragma config FPLLODIV=DIV_1 // Postscaler for PLL, output divided by 1
#pragma config FPBDIV=DIV_2 // 2 = PBCLK is SYSCLK divided by 2 (80MHz/2 = 40MHz)
#pragma config FWDTEN=OFF // Watch Dog Timer (WDT) is not enabled. It can be enabled by software
#pragma config CP=OFF // Code-Protect, 1 = OFF/Disabled
#pragma config BWP=OFF // Boot Flash Write-protect, 1 = OFF/Disabled
#pragma config POSCMOD=XT // Primary oscillator configuration, HS = HS Oscillator mode selection
#pragma config FNOSC=PRIPLL // Oscillator selection, PRIPLL = Primary Oscillator with PLL module
#pragma config OSCIOFNC=OFF // CLKO output disabled
#pragma config FSOSCEN=OFF // Disable secondary Oscillator
int UART_RX_Count; // Counter variable for the UART1 receiver interrupt
int UART_TX_Count; // Counter varible for the UART1 transmitted interrupt
unsigned char RD_SER_NUM; // Variable to store command to read serial number
unsigned char UART_RX_OUTPUT; // Variable to store the UART output
unsigned char i;
void UART1_Init(void){
// UART1 initialization
U1MODEbits.ON = 1; // UART1 is enabled
U1MODEbits.SIDL = 0; // Continue operation in idle mode
U1MODEbits.IREN = 0; // Disable IrDA (IrDA Encoder and Decoder Enable bit)
U1MODEbits.RTSMD = 1; // !U1RTS! pin is in Simplex mode, 0 = !U1RTS! pin is in Flow Control mode
U1MODEbits.UEN = 0; // UxTX and UxRX pins are enabled and used; UxCTS and UxRTS/UxBCLK pins are controlled by corresponding bits in the PORTx register
U1MODEbits.WAKE = 1; // Enable Wake-up on Start bit Detect During Sleep Mode bit
U1MODEbits.LPBACK = 0; // UARTx Loopback Mode Select bit, 0 = disabled, loopback = UxTX output is internally connected to the UxRX input
U1MODEbits.PDSEL = 2; // Parity and Data Selection bits, 10 = 8-bit data, odd parity
U1MODEbits.STSEL = 0; // Stop Selection bit, 0 = 1 stop bit
U1MODEbits.BRGH = 0; // High Baud Rate Enable bit, 0 = Standard Speed mode 16x baud clock enabled
U1MODEbits.RXINV = 1; // Receive Polarity Inversion bit, 1 = UxRX Idle state is 0
U1STAbits.URXEN = 1; // 1 = UART1 receiver is enabled. U1RX pin is controlled by UARTx (if ON = 1)
U1STAbits.UTXEN = 1; // 1 = UART1 transmitter is enabled. U1TX pin is controlled by UARTx (if ON = 1)
U1STAbits.UTXINV = 1; // Transmit Polarity Inversion bit, 1 = UxTX Idle state is 0
U1STAbits.ADM_EN = 0; // 0 = Automatic Address Detect mode is disabled
U1BRG = 259; // Baud Rate Divisor bits (0-15 bits), set baud rate, 9600 # 40 MHz PBclk
__builtin_disable_interrupts(); // Tell CPU to stop paying attention to interrupts
INTCONbits.MVEC = 1; // Multi Vector interrupts
U1STAbits.URXISEL = 0; // 0x = Interrupt flag bit is set when a character is received
U1STAbits.UTXISEL = 1; // 01 = Interrupt flag bit is set when all characters have been transmitted
IPC6bits.U1IP = 5; // Set UART1 priority 5 of 7
IPC6bits.U1IS = 0; // Set UART1 sub priority to 0
IFS0bits.U1RXIF = 0; // Clear UART1 RX interrupt flag
IFS0bits.U1TXIF = 0; // Clear UART1 TX interrupt flag
IEC0bits.U1RXIE = 1; // Enable UART1 RX ISR
__builtin_enable_interrupts(); // Tell CPU to start paying attention to interrupts again
UART_RX_Count = 0; // Set initial UART1 received interrupts count to 0
UART_TX_Count = 0; // Set initial UART1 transmit interrupts count to 0
}
void __ISR(_UART_1_VECTOR, IPL5SRS) UART1_INT(void){
if(INTGetFlag(INT_U1RX)){ // Check if UART1 RX interrupt was triggered
LED1 = ~LED1; // Toggle LED1
UART_RX_Count++; // Add 1 to UART1 RX interrupt occurrence counter
// UART_RX_OUTPUT = U1RXREG; // Read UART1 RX buffer/register
U1TXREG = U1RXREG; // Transmit the received data back
// U1STAbits.OERR = 0; // Clear UART1 buffer overflow
IFS0bits.U1RXIF = 0; // Clear UART1 RX interrupt flag
}else{
if(INTGetFlag(INT_U1TX)){ // Check if UART1 TX interrupt was triggered
UART_TX_Count++; // Add 1 to UART1 TX interrupt occurrence counter
IEC0bits.U1TXIE = 0; // Disable UART1 TX ISR
IFS0bits.U1TXIF = 0; // Clear UART1 TX interrupt flag
}
}
}
// DelayMs creates a delay of given milliseconds using the Core Timer
void DelayMs(WORD delay){
unsigned int int_status;
while( delay-- ){
int_status = INTDisableInterrupts();
OpenCoreTimer(GetSystemClock() / 200);
INTRestoreInterrupts(int_status);
mCTClearIntFlag();
while( !mCTGetIntFlag() );
}
mCTClearIntFlag();
}
int main(){
UART1_Init(); // Call the initializations function of UART1
LED1_TRIS = 0; // Set the LED1 as an output
UART1TX_TRIS = 0; // Set UART1 TX pin as output
UART1RX_TRIS = 1; // Set UART1 RX pin as input
LED1 = 0; // Turn off LED1
while(1){
// DelayMs(1000);
// IEC0bits.U1TXIE = 1; // Enable UART1 TX ISR
// U1TXREG = 0x41; // Send command to U1TXREG
}
return 0;
}
As You are using PIC32MX795F512H, You can use the MPLAB Harmony framework tool for creating your project. So that you need not to play on bit level and stuck in minor error or most probabaly typo error.
Its convinient to generate drivers and all framework properly.
Thanks and regards
Ravi
Using Harmony will actually help you avoid simple errors like the one you have encountered. Especially for the clocks you even have auto calculating functions decreasing your implementation time significantly.

No interrupts being triggered in UART Receive on PIC18F2680

I have been working with this code for days and cannot figure out why my interrupts are not being triggered. I know data is coming through successfully because I used a probe on a logic analyzer, also my baud rate is correct as I can transmit with UART successfully.
At this point I'm lost, I've read the datasheet over and over and can't figure out my problem. I will try to include only the relative code but enough that you can see how things work in my project.
Please let me know if you see issues with this code.
Thank you!
Code snippets from main.c:
// USART RX interrupt priority
IPR1bits.RCIP = 0;
IPR1bits.TXIP = 0;
// configure the hardware USART device
OpenUSART(USART_TX_INT_OFF & USART_RX_INT_ON & USART_ASYNCH_MODE & USART_EIGHT_BIT &
USART_CONT_RX & USART_BRGH_LOW, 14);
Code snippets from interrupts.c
//----------------------------------------------------------------------------
// Low priority interrupt routine
// this parcels out interrupts to individual handlers
#pragma code
#pragma interruptlow InterruptHandlerLow
// This works the same way as the "High" interrupt handler
void InterruptHandlerLow() {
// check to see if we have an interrupt on USART RX
if (PIR1bits.RCIF) {
PIR1bits.RCIF = 0; //clear interrupt flag
uart_recv_int_handler();
}
// check to see if we have an interrupt on USART TX
if (PIR1bits.TXIF && PIE1bits.TXIE) {
// cannot clear TXIF, this is unique to USART TX
// so just call the handler
uart_tx_int_handler();
}
}
UART RX Interrupt Handler snippet:
void uart_recv_int_handler() {
int msgLen;
//if (DataRdyUSART()) {
uc_ptr->buffer[uc_ptr->buflen] = RCREG;
//uc_ptr->buffer[uc_ptr->buflen] = ReadUSART();
uc_ptr->buflen++;
}
}
Did you
- Set trisC6/7 correctly?
- if you have a part with analog inputs multiplexed on those pins, did you disable them?
- Is your BRG value validated for this part and these oscillator settings?
See also
http://www.piclist.com/techref/microchip/rs232.htm
I migrated to dspic, but I used to do the serial receive under interrupt. This I had in the interrupt (serialin1 is a power of two circular buffer, lastserialin1 the pointer into it, and ser1bufinmask is size of buffer-1)
if (PIR1bits.RCIF == 1) /* check if RC interrupt (receive USART) must be serviced
{
while (PIR1bits.RCIF == 1) /* flag becomes zero if buffer/fifo is empty */
{
lastserialin1=(lastserialin1+1)&ser1bufinmask;
serialin1[lastserialin1]=RCREG;
}
}
To initialize the uart I had:
// Configure USART
TXSTA = 0x20; // transmit enable
RCSTA = 0x90; // spen en cren
RCONbits.IPEN = 1; /* Interrupt Priority Enable Bit. Enable priority levels on interrupts */
INTCONbits.GIE = 1; /* Set GIE. Enables all high priority unmasked interrupts */
INTCONbits.GIEL = 1; /* Set GIEL. Enables all low priority unmasked interrupts */
TRISCbits.TRISC6 = 0; // page 237
TRISCbits.TRISC7 = 1; // page 237
Open1USART (
USART_TX_INT_OFF
&
USART_RX_INT_ON &
USART_ASYNCH_MODE &
USART_EIGHT_BIT & // 8-bit transmit/receive
USART_CONT_RX & // Continuous reception
// USART_BRGH_HIGH, 155); // High baud rate, 155 eq 19k2
USART_BRGH_HIGH, brgval); // High baud rate, 25 eq 115k2
IPR1bits.RCIP = 0;
PIR1bits.RCIF = 0;
with brgval calculated using
#define GetInstructionClock() (GetSystemClock()/4)
#define GetPeripheralClock() GetInstructionClock()
// See if we can use the high baud rate setting
#if ((GetPeripheralClock()+2*BAUD_RATE)/BAUD_RATE/4 - 1) <= 255
#define BRGVAL ((GetPeripheralClock()+2*BAUD_RATE)/BAUD_RATE/4 - 1)
#define BRGHVAL (1)
#else // Use the low baud rate setting
#define BRGVAL ((GetPeripheralClock()+8*BAUD_RATE)/BAUD_RATE/16 - 1)
#define BRGHVAL (0)
#endif