PIC32 UART transmission trouble, no data being transmitted - uart

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

Related

What is wrong with this PIC16F877A HCSR04 example?

I am working on distance sensor with PIC16F877A.
I am using MPLAB IDE AND XC8 compiler.
My goal is to gradually turn on the right leds at certain distance levels, but the leds are blinking unstable. What am I doing wrong? distance/5
When it measures 5 cm, it is 5/5 and the result is 1 and 1 led is on.
When it measures 10 cm, it is 10/5 and the result is 2 and 2 leds are on.
When you measure 15 cm, it is 15/5 and the result is 3 and 3 LEDs are on.
When you measure 20 cm, it is 20/5 and the result is 4 and 4 leds are on.
If the distance is less than 5 cm or above 20 cm, no led lights are on
https://i.stack.imgur.com/fFKQg.png
#include <xc.h>
#include <pic16f877a.h>
#pragma config FOSC = XT // Oscillator Selection bits (XT oscillator)
#pragma config WDTE = OFF // Watchdog Timer Enable bit (WDT disabled)
#pragma config PWRTE = OFF // Power-up Timer Enable bit (PWRT disabled)
#pragma config BOREN = OFF // Brown-out Reset Enable bit (BOR disabled)
#pragma config LVP = OFF // Low-Voltage (Single-Supply) In-Circuit Serial Programming Enable bit (RB3 is digital I/O, HV on MCLR must be used for programming)
#pragma config CPD = OFF // Data EEPROM Memory Code Protection bit (Data EEPROM code protection off)
#pragma config WRT = OFF // Flash Program Memory Write Enable bits (Write protection off; all program memory may be written to by EECON control)
#pragma config CP = OFF // Flash Program Memory Code Protection bit (Code protection off)
#define _XTAL_FREQ 4000000
#define trigger RC2
#define echo RC3
int calc_distance();
int calc_distance()
{
int distance=0;
trigger=1;
__delay_us(10);
trigger=0;
while(!echo); // normally the echo pin is logic 0. If we toggle the zero and throw it into the while, it returns idle until the echo arrives (until the signal becomes logic 1).
TMR1ON=1;//In the upper loop, while returning the command empty, echo comes and exits the upper loop and timer1 is activated.
while(echo);
TMR1ON=0;//
distance=TMR1/58;
return distance;
}
void main(void)
{
int dist=0; // Create Distance Variable
TRISB = 0x00; // Set PORTB To Be Output Port (All The 8 Pins)
PORTB = 0x00; // Set PORTB To Be LOW For initial State
TRISC2 = 0; // Set RC2 To Be Output Pin ( Trigger )
RC2 = 0;
TRISC3 = 1; // Set RC3 To Be Input Pin ( Echo )
//--[ Configure Timer Module To Operate in Timer Mode ]--
// Clear The Pre-Scaler Select Bits
T1CKPS0=0;
T1CKPS1=0;
TMR1CS=0;// Choose The Local Clock As Clock Source
while(1)
{
calc_distance();
dist = calc_distance()/5;
if(dist==1)
{PORTB = 0x01; __delay_ms(50);}
if(dist==2)
{PORTB = 0x03; __delay_ms(50);}
if(dist==3)
{PORTB = 0x07; __delay_ms(50);}
if(dist==4)
{PORTB = 0x0F; __delay_ms(50);}
else
{PORTB = 0x00; __delay_ms(50);}
}
return;
}

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;

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.

PIC32MX dma not triggered by adc

I’m trying to make a little application on the pic32mx795f512l but I can’t get it to work.
What I want to achieve is that adc continuously gets the current analog value from channel 0 with the highest possible rate. If the 16 Word buffer is filled, it should trigger the dma to save this buffer in ram. The dma should trigger an Interrupt if the ram buffer is full. So i could start the calculation in the main loop.
My problem now is that the dma is not triggered at all. When I enable the interrupt on the adc the main loop isn't running.
Does anyone know what I did wrong?
Here is my source code:
/*** DEVCFG0 ***/
#pragma config DEBUG = OFF
#pragma config ICESEL = ICS_PGx2
#pragma config PWP = 0xff
#pragma config BWP = OFF
#pragma config CP = OFF
/*** DEVCFG1 ***/
#pragma config FNOSC = PRIPLL
#pragma config FSOSCEN = ON
#pragma config IESO = ON
#pragma config POSCMOD = XT
#pragma config OSCIOFNC = OFF
#pragma config FPBDIV = DIV_8
#pragma config FCKSM = CSDCMD
#pragma config WDTPS = PS1048576
#pragma config FWDTEN = ON
/*** DEVCFG2 ***/
#pragma config FPLLIDIV = DIV_2
#pragma config FPLLMUL = MUL_20
#pragma config FPLLODIV = DIV_1
#pragma config UPLLIDIV = DIV_2
#pragma config UPLLEN = ON
/*** DEVCFG3 ***/
#pragma config USERID = 0xffff
#pragma config FSRSSEL = PRIORITY_7
#pragma config FMIIEN = ON
#pragma config FETHIO = ON
#pragma config FCANIO = ON
#pragma config FUSBIDIO = ON
#pragma config FVBUSONIO = ON
int adcValues[128];
void __ISR(_ADC_VECTOR, IPL7SRS) ADCHandler(void) // interrupt every 8 samples
{
IFS1bits.AD1IF = 0; // clear interrupt flag
}
void __ISR(_DMA0_VECTOR, ipl5) _IntHandlerSysDmaCh0(void)
{
int dmaFlags=DCH0INT&0xff; // read the interrupt flags
/*
perform application specific operations in response to any interrupt flag set
*/
DCH0INTCLR=0x000000ff; // clear the DMA channel interrupt flags
IFS1CLR = 0x00010000; // Be sure to clear the DMA0 interrupt flags
}
unsigned int __attribute__((always_inline)) _VirtToPhys(const void* p) {
return (int) p < 0 ? ((int) p & 0x1fffffffL) : (unsigned int) ((unsigned char*) p + 0x40000000L);
}
void initADC(void) {
AD1PCFG = 0xFFFB; // PORTB = Digital; RB2 = analog
AD1CON1 = 0x0000; // SAMP bit = 0 ends sampling
// and starts converting
// turn ADC on | unsigned 32-bit int output | auto-convert after sample finished |
// don?t stop conversions at interrupt | auto-sample after conversion finished
AD1CON1 = (1 << 15) | (4 << 8) | (7 << 5) | (0 << 4) | (1 << 2);
IPC6bits.AD1IP = 7; // INT priority level 7, for shadow register set
IFS1bits.AD1IF = 0; // clear interrupt flag
IEC1bits.AD1IE = 1; // enable interrupts
AD1CHS = 0x00020000; // Connect RB2/AN2 as CH0 input
AD1CON1SET = 0x8000; // turn on the ADC
}
void initDMA(void) {
IEC1CLR=0x00010000; // disable DMA channel 0 interrupts
IFS1CLR=0x00010000; // clear any existing DMA channel 0 interrupt flag
DMACONSET=0x00008000; // enable the DMA controller
DCH0CON=0x03; // channel off, priority 3, no chaining
DCH0ECON=0;
DCH0ECONbits.CHSIRQ=_ADC_IRQ; // This should map the AD1 ? ADC1 Convert Done Interrupt to start the dma IRQ no. 33 Vector no. 27
// program the transfer
DCH0SSA=_VirtToPhys(&ADC1BUF0); // transfer source physical address
DCH0DSA=_VirtToPhys(adcValues); // transfer destination physical address
DCH0SSIZ=16; // source size 16 bytes
DCH0DSIZ=128; // destination size NUM_SAMPS bytes
DCH0CSIZ=16; // 16 bytes transferred per event
DCH0INTCLR=0x00ff00ff; // clear existing events, disable all interrupts
//DCH0INTSET=0x00090000; // enable Block Complete and error interrupts
DCH0INTbits.CHDDIF=1; //1 = Channel Destination Pointer has reached end of destination (CHDPTR = CHDSIZ)
IPC9CLR=0x0000001f; // clear the DMA channel 0 priority and sub-priority
IPC9SET=0x00000016; // set IPL 5, sub-priority 2
IEC1SET=0x00010000; // enable DMA channel 0 interrupt
DCH0CONSET=0x80; // turn channel on
}
void main(){
INTDisableInterrupts(); // disable interrupts before configuring ADC
initADC();
initDMA();
INTEnableSystemMultiVectoredInt(); // enable interrupts at CPU
while(1);
}
It seems to me that the issue is that you have two different sources that are trying to consume the interrupt vector from the ADC, both the DMA channel and an ISR.
From my experience this means that only one of the two will get the interrupt vector, and it tends to be the ISR.
I recommend that you remove the ISR for the ADC. Especially since it seems that you are only reseting the interrupt flag, but it should be possible to configure the ADC to automatically reset the flag and interrupt every number of samples (I've been able to do this on the PIC32mx256f128B)