Reading a non-null terminated input at serial? - mbed

I am working with mbed, the LPC1768. The serial input to the mbed is a unsigned character array which is not null-terminated. I don't get anything with getc(), how to get the input?

the null character is 0 so if you need get it u can using a Buffer Counter or a ovf variable to detect received a character!!
Config your UART0,1 by this Setting:
comment UART0 or UART1 if not use it!
so u can select UARTs with #define in: option->C/C++->Define:__UART0 or __UART1
void SER_Init (void) {
#ifdef __UART0 /* UART0 */
LPC_SC->PCONP |= ((1 << 3) | (1 << 15)); /* enable power to UART0 & IOCON */
LPC_PINCON->PINSEL0 |= (1 << 4); /* Pin P0.2 used as TXD0 */
LPC_PINCON->PINSEL0 |= (1 << 6); /* Pin P0.3 used as RXD0 */
#else /* UART1 */
LPC_SC->PCONP |= ((1 << 4) | (1 << 15)); /* enable power to UART1 & IOCON */
LPC_PINCON->PINSEL4 |= (2 << 0); /* Pin P2.0 used as TXD1 */
LPC_PINCON->PINSEL4 |= (2 << 2); /* Pin P2.1 used as RXD1 */
#endif
UART->LCR = 0x83; /* 8 bits, no Parity, 1 Stop bit */
UART->DLL = 9; /* 115200 Baud Rate # 25.0 MHZ PCLK*/
UART->FDR = 0x21; /* FR 1,507, DIVADDVAL=1, MULVAL=2 */
UART->DLM = 0; /* High divisor latch = 0 */
UART->LCR = 0x03; /* DLAB = 0 */
}
------> and use this func. for Get Character:
/*----------------------------------------------------------------------------
Read character from Serial Port (blocking read)
*----------------------------------------------------------------------------*/
int SER_GetChar (void) {
while (!(UART0->LSR & 0x01));
return (UART0->RBR);
}

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.

Attiny 84 Communicating with RTC Through SPI Troubles

I am currently trying to use an ATtiny84 to communicate with an RTC (DS1305) through SPI to make an buzzer vibrate every variable amount of time. I've been trying to set alarm0 on the DS1305. However, the 84 does not "technically" have SPI. It has USI which can be programmed to be like SPI. I was wondering if any of you could review my code/ board connections and let me know if you see any problems. The current problem is that I cannot get any communication going through SPI and I am having trouble finding what the issue could be.
Current board connections:
ATtiny84 | DS1305
MOSI ------ DI
MISO ------ DO
USCLK ---- CLK
Datasheets:
Attiny84
DS1305
/*
* Atmel_Jolt_Code.c
*
* Created: 11/28/2018 10:44:30 PM
* Author : Nick Hulsey
*/
#include <avr/io.h>
#define F_CPU 16000000UL
#include <avr/interrupt.h>
#include <util/delay.h>
//variables for SPI
#define SPI_DDR_PORT DDRA
#define CE_PIN DDA3 //I ADDED *****
#define DO_DD_PIN DDA5 // SHOULD WE
#define DI_DD_PIN DDA6 // THEM FLIP
#define USCK_DD_PIN DDA4
#define SPI_MODE0 0x00
#define SPI_MODE1 0x04
#define MOTOR_PIN DDA7 //I ADDED *****
void SPI_begin();
void setDataMode(uint8_t spiDataMode);
uint8_t transfer(uint8_t spiData);
void flipLatch(uint8_t on);
int main(void)
{
SPI_begin();
setDataMode(SPI_MODE1);
DDRA |= (1 << MOTOR_PIN);
//**startup**
uint8_t status_register = 0x10;
uint8_t control_register = 0x8F;
uint8_t control_byte = 0x05;
uint8_t alarm_registers[] = {0x8A, 0x89, 0x88, 0x87};
//set control
flipLatch(1);
transfer(control_register);
transfer(0);
flipLatch(0);
flipLatch(1);
transfer(control_register);
transfer(control_byte);
flipLatch(0);
//set alarm:
for (int i = 0; i < 4; i++){
flipLatch(1);
transfer(alarm_registers[i]);
transfer(0x80); //0b10000000
flipLatch(0);
}
//THIS MIGHT NEED WORK
//GIMSK |= (1 << PCIE1);//set external interrupt (A1)
PCMSK0 |= (1 << PCINT1);
sei();
while (1) //our main loop
{
//reading the flag from the status register
uint8_t status = transfer(status_register);
if(status == 0x01){//if alarm 0 has been flagged
PORTA ^= (1 << MOTOR_PIN);
_delay_ms(100);
}
}
}
//if A1 has changed state at all this function will fire
ISR(PCINT1_vect){
PORTA ^= (1 << MOTOR_PIN);//invert motor power
_delay_ms(100);
}
void SPI_begin(){
USICR &= ~((1 << USISIE) | (1 << USIOIE) | (1 << USIWM0));//Turn off these bits
USICR |= (1 << USIWM0) | (1 << USICS1) | (1 << USICLK);//Turn on these bits
//REVIEW THIS PAGE 128
//external,positive edge software clock
//What does this mean
SPI_DDR_PORT |= 1 << USCK_DD_PIN; // set the USCK pin as output
SPI_DDR_PORT |= 1 << DO_DD_PIN; // set the DO pin as output
SPI_DDR_PORT |= 1 << CE_PIN;// ******** I ADDED
SPI_DDR_PORT &= ~(1 << DI_DD_PIN); // set the DI pin as input
}
void setDataMode(uint8_t spiDataMode)
{
if (spiDataMode == SPI_MODE1)
USICR |= (1 << USICS0);
else
USICR &= (1 << USICS0);
}
//returns values returned from the IC
uint8_t transfer(uint8_t spiData)
{
USIDR = spiData;
USISR = (1 << USIOIF); // clear counter and counter overflow interrupt flag
//ATOMIC_BLOCK(ATOMIC_RESTORESTATE) // ensure a consistent clock period
//{
while ( !(USISR & (1 << USIOIF)) ) USICR |= (1 << USITC);
//}
return USIDR;
}
void flipLatch(uint8_t on){
if (on == 1)
PORTA |= (1 << CE_PIN);
else
PORTA &= ~(1 << CE_PIN);
}

Why am I only getting 0xFF when reading from the LIS3DSH accelerometer on the STM32F407G-Disc1 MCU?

So I'm learning embedded development, and I recently learned the basics of SPI. As a project, I wanted to communicate with the LIS3DSH accelerometer on my STM32F407G-DISC1 board using only the CMSIS headers.
I pasted the entire code below, but I'll explain it first because no one wants to read all that code.
As a reference, these are the pins needed (according to the MCU's datasheet) to communicate via SPI:
PA5 - SPI1_SCK
PA7 - SPI1_MOSI
PA6 - SPI1_MISO
PE3 - CS_I2C/SPI
Here's the steps I took in my code:
Enabled the clock for GPIOA and GPIOE using the AHB1ENR register.
For GPIOA, I set the three pins as alternate function, output is push-pull, speed is low, no pull-up/pull-down, and configured the alternate function as SPI.
For GPIOE, set it as GPIO mode, push-pull, low speed, pull-up, and then set it high (as in wrote to the BSSR register).
Enabled the clock for SPI using the APB2ENR register.
Configured SPI1: first disabled it, enabled 2-line unidirectional mode, set baud rate to fPCL/16 since the APB2 peripheral clock is 84MHz and the max clock of the accelerometer is 10MHz. Then set clock phase and polarity to 1. 8-bit data frame, MSB first, enabled software slave management, and also enabled master configuration. Finally, enabled SPI1.
After all this, I transmit 0x63 to the 0x20 register of the accelerometer. This sets the output rate to 100Hz and enables both the x and y axis. I have no idea if this is actually working. I'm assuming it is because the TX buffer is empty when I check the SPI status register.
Then to test whether I can recieve, I attempt to get the data from the WHO_AM_I register of the accelerometer. But I only see garbage data when I debug it (0xFF).
I've googled around to see why this may be, and a lot of people suggested that the clock polarity and phase may be incorrect. However, I've checked it multiple times, and I'm fairly certain I configured it properly.
I've tried setting interrupts. During the interrupt, even though RXNE (RX buffer not empty) is true, it still reads only 0xFF. I'm stumped as to why this is happening.
The code is below. The starting point is accelerometer_init(). The reading of the data from the WHO_AM_I register is in turn_on_accelerometer().
#include <stdint.h>
#include <stdbool.h>
#include "stm32f4xx.h"
#include "accelerometer.h"
static void gpio_clock_enable(void);
static void gpio_a_init(void);
static void gpio_e_init(void);
static void accelerometer_clock_enable(void);
static void configure_accelerometer(void);
static void pull_slave_high(void);
static void pull_slave_low(void);
static void turn_on_accelerometer(void);
static void wait_till_transmit_complete(void);
static void transmit_only(uint8_t address, uint8_t data);
static void receive_dummy_data(void);
void accelerometer_init(void) {
gpio_clock_enable();
gpio_a_init();
gpio_e_init();
accelerometer_clock_enable();
configure_accelerometer();
turn_on_accelerometer();
}
void gpio_clock_enable(void) {
RCC_TypeDef *rcc = RCC;
rcc->AHB1ENR |= (1 << 0) | (1 << 4);
}
void gpio_a_init(void) {
GPIO_TypeDef *gpio_a = GPIOA;
// Reset mode and set as alternate function
gpio_a->MODER &= ~(0x3 << 10) & ~(0x3 << 12) & ~(0x3 << 14);
gpio_a->MODER |= (0x2 << 10) | (0x2 << 12) | (0x2 << 14);
// Set output to PP
gpio_a->OTYPER &= ~(1 << 5) & ~(1 << 6) & ~(1 << 7);
// Set speed to low
gpio_a->OSPEEDR &= ~(0x3 << 10) & ~(0x3 << 12) & ~(0x3 << 14);
// Set to no pull-up / pull-down
gpio_a->PUPDR &= ~(0x3 << 10) & ~(0x3 << 12) & ~(0x3 << 14);
// Reset alternate function and set to SPI
gpio_a->AFR[0] &= ~(0xF << 20) & ~(0xF << 24) & ~(0xF << 28);
gpio_a->AFR[0] |= (0x5 << 20) | (0x5 << 24) | (0x5 << 28);
}
void gpio_e_init(void) {
GPIO_TypeDef *gpio_e = GPIOE;
// Set as general purpose output mode
gpio_e->MODER &= ~(0x3 << 6);
gpio_e->MODER |= (1 << 6);
// Set as push pull
gpio_e->OTYPER &= ~(1 << 3);
// Set as low speed
gpio_e->OSPEEDR &= ~(0x3 << 6);
// Set to pull up
gpio_e->PUPDR &= ~(0x3 << 6);
gpio_e->PUPDR |= (1 << 6);
// Set it high
pull_slave_high();
}
void accelerometer_clock_enable(void) {
RCC_TypeDef *rcc = RCC;
rcc->APB2ENR |= (1 << 12);
}
void configure_accelerometer(void) {
SPI_TypeDef *spi_1 = SPI1;
// First disable it while we configure SPI
spi_1->CR1 &= ~(1 << 6);
// 2-line unidirectional data mode enabled
spi_1->CR1 &= ~(1 << 15);
// Reset baud rate and set to fPCLK/16
// because APB2 peripheral clock currently is 84 MHz
// and the max clock of the accelerometer is 10 MHz.
spi_1->CR1 &= ~(0x7 << 3);
spi_1->CR1 |= (0x3 << 3);
// Set clock phase to 1
spi_1->CR1 |= (1 << 0);
// Set clock polarity to 1
spi_1->CR1 |= (1 << 1);
// 8 bit data frame format
spi_1->CR1 &= ~(1 << 11);
// MSB first
spi_1->CR1 &= ~(1 << 7);
// Software slave management enabled
spi_1->CR1 |= (1 << 9);
spi_1->CR1 |= (1 << 8);
// Master configuration enabled
spi_1->CR1 |= (1 << 2);
// SS output enabled
// spi_1->CR2 |= (1 << 2);
// Enable SPI
spi_1->CR1 |= (1 << 6);
// Wait a little bit for accelerometer to turn on
for (int i=0; i<1000000; i++);
}
void pull_slave_high(void) {
// Wait until SPI is no longer busy
SPI_TypeDef *spi_1 = SPI1;
while ((spi_1->SR >> 7) & 1);
GPIO_TypeDef *gpio_e = GPIOE;
gpio_e->BSRR |= (1 << 19);
}
void pull_slave_low(void) {
// Wait until SPI is no longer busy
SPI_TypeDef *spi_1 = SPI1;
while ((spi_1->SR >> 7) & 1);
GPIO_TypeDef *gpio_e = GPIOE;
gpio_e->BSRR |= (1 << 3);
}
void turn_on_accelerometer(void) {
// Set output data rate to 100Hz
// and enable X-axis, Y-axis.
transmit_only(0x20, 0x63);
receive_dummy_data();
// Temp test checking the WHO_AM_I register on the accelerometer.
SPI_TypeDef *spi_1 = SPI1;
pull_slave_low();
wait_till_transmit_complete();
uint8_t address = 0x0F | 0x80;
spi_1->DR = address;
wait_till_transmit_complete();
while (true) {
volatile bool is_busy = (spi_1->SR >> 7) & 1;
volatile bool is_rx_buffer_not_empty = (spi_1->SR >> 0) & 1;
if (!is_busy && is_rx_buffer_not_empty) {
break;
}
}
volatile uint32_t data = spi_1->DR;
pull_slave_high();
}
/*
* Transmit is synchronous.
*/
void transmit_only(uint8_t address, uint8_t data) {
SPI_TypeDef *spi_1 = SPI1;
// Select the accelerometer as the slave
pull_slave_low();
// Wait till transmit buffer is ready
wait_till_transmit_complete();
spi_1->DR = address;
// Wait till transmit buffer is ready
wait_till_transmit_complete();
spi_1->DR = data;
// Wait till transmit buffer has been read
wait_till_transmit_complete();
// Deselect the slave
pull_slave_high();
}
void wait_till_transmit_complete(void) {
SPI_TypeDef *spi_1 = SPI1;
while (true) {
volatile bool is_busy = (spi_1->SR >> 7) & 1;
volatile bool is_transmit_buffer_empty = (spi_1->SR >> 1) & 1;
if (!is_busy && is_transmit_buffer_empty) {
break;
}
}
}
void receive_dummy_data(void) {
SPI_TypeDef *spi_1 = SPI1;
spi_1->DR;
spi_1->SR;
}
You are working with SPI incorrectly.
This bus works in this way:
master (MCU) sends byte in MOSI
line at the same (!) time slave (LIS) sends byte in MISO line. In this moment slave dont know, what exactly byte master transfers to it.
To transfer one byte, you should:
write byte in data register
wait for completition of transfer
read data register
Thus, to read WHO_AM_I register, we obtain next sequence:
init SPI
flush data register (just read SPI->DR)
send command
wait
read dummy data (your 0xFF)
write second byte (0x00 or 0xFF, it doesn't matter)
wait
read correct answer from LIS

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?

How to read from and write to EEPROM suing SPI communication

I am using PIC32MX350F128L Microcontroller to read from and write to EEPROM(SST26VF032B) using SPI communication. SPI communication in this program is working, I have checked it by sending JEDEC code which is provided in the SST26VF032B datasheet. So when i send 0x9F i am getting 3 bytes of data as mentioned in the datasheet. When i run now i am sending a string of data to a specific address of eeprom and getting 0xff in return. I am erasing the eeprom before writing into it. So i think i am getting 0xff after erasing the eeprom. The writing, reading operations are not working. If i send a string of value or a BYTE i am getting 0xff in return. So can u guys please suggest me where i am going wrong. I am using UART for debugging purpose to read values recieved through spi communication. The complete code is below, i am using MPLAB X.
Best Regards
Sandesh
#include <xc.h>
#include <stdio.h>
#include <plib.h>
#include <p32xxxx.h>
/* Configuration Bits */
#pragma config FSRSSEL = PRIORITY_7 // Shadow Register Set Priority Select (SRS Priority 7)
#pragma config PMDL1WAY = ON // Peripheral Module Disable Configuration (Allow only one reconfiguration)
#pragma config IOL1WAY = ON // Peripheral Pin Select Configuration (Allow only one reconfiguration)
// DEVCFG2
#pragma config FPLLIDIV = DIV_2 // PLL Input Divider (2x Divider)
#pragma config FPLLMUL = MUL_20 // PLL Multiplier (20x Multiplier)
#pragma config FPLLODIV = DIV_1 // System PLL Output Clock Divider (PLL Divide by 1)
// DEVCFG1
#pragma config FNOSC = PRIPLL // Oscillator Selection Bits (Primary Osc (XT,HS,EC))
#pragma config FSOSCEN = ON // Secondary Oscillator Enable (Enabled)
#pragma config IESO = ON // Internal/External Switch Over (Enabled)
#pragma config POSCMOD = HS // Primary Oscillator Configuration (XT osc mode)
#pragma config OSCIOFNC = ON // CLKO Output Signal Active on the OSCO Pin (Enabled)
#pragma config FPBDIV = DIV_1 // Peripheral Clock Divisor (Pb_Clk is Sys_Clk/8)
#pragma config FCKSM = CSECME // Clock Switching and Monitor Selection (Clock Switch Disable, FSCM Disabled)
#pragma config WDTPS = PS1048576 // Watchdog Timer Postscaler (1:1048576)
#pragma config WINDIS = OFF // Watchdog Timer Window Enable (Watchdog Timer is in Non-Window Mode)
#pragma config FWDTEN = OFF // Watchdog Timer Enable (WDT Disabled (SWDTEN Bit Controls))
#pragma config FWDTWINSZ = WINSZ_25 // Watchdog Timer Window Size (Window Size is 25%)
// DEVCFG0
#pragma config DEBUG = OFF // Background Debugger Enable (Debugger is Disabled)
#pragma config JTAGEN = OFF // JTAG Enable (JTAG Disabled)
#pragma config ICESEL = ICS_PGx2 // ICE/ICD Comm Channel Select (Communicate on PGEC2/PGED2)
#pragma config PWP = OFF // Program Flash Write Protect (Disable)
#pragma config BWP = OFF // Boot Flash Write Protect bit (Protection Disabled)
#pragma config CP = OFF // Code Protect (Protection Disabled)
/* MACRO DEFINITIONS */
/* Defining the Slave Select Pin */
#define SS LATDbits.LATD9
/* Defining the System Clock Frequency */
#define SYSCLK 40000000
/* Macro to get array size in bytes
* note that array size can't be found after passing pointer to a function */
#define LEN(x) (sizeof(x) / sizeof(x[0]))
/* SST26VF032B EEPROM instructions */
/* Write Enable */
#define WREN 0x06
/* Write Disable */
#define WRDI 0x04
/* Initialize Start of Write Sequence */
#define WRITE 0x02
/* Initialize Start of Read Sequence */
#define READ 0x03
/* Erase all sectors of Memory */
#define CE 0xc7
/* Read STATUS Register */
#define RDSR 0x05
/* Function Prototypes */
/* UART bit configuration */
void Bitconfig_uart(void);
/* SPI Initialization */
void SPI1_Init(void);
/* UART Initialization */
void Init_uart(void);
/* Send a Character Byte through UART */
void UART5PutChar(char Ch);
/* Function to Read and Write SPI1 buffer */
int SPI1_transfer( int b);
/* Function to check the Status of SPI */
void waitBusy();
/* Function to erase the contents in EEPROM */
void eraseEEPROM();
/* Function to Read data from EEPROM */
void readEEPROM( int address, char* loadArray, int loadArray_size);
/* Function to Write to EEPROM */
void writeEEPROM( int address, char* storeArray, int storeArray_size);
/* Global Variables Declaration */
/* Declare variables to check the functionality of EEPROM */
int i,j = 0;
char st = 0x9F;
char rec;
int x,y,z;
/*******************************************************************************
* Function Name: main()
********************************************************************************
* Summary:
* Initializes SPI
* Erase EEPROM
* Writes to EEPROM
* Read from EEPROM
*
* Parameters:
* None.
*
* Return:
* None.
*
*******************************************************************************/
int main()
{
int i;
/* Clock Setting */
SYSTEMConfigPerformance(SYSCLK);
/* UART bit configuration */
Bitconfig_uart();
/* Set the Controller OScillator Register bits */
//OSCCON = 0x00002200;
/* Initialize a String to Write to EEPROM and an array to Read back contents */
char writeData[] = "123456789ABCDEF";
/* Array to read 35 bytes of data */
char readData[15];
/* SPI Initialization */
SPI1_Init();
/* UART Initialization */
Init_uart();
/* Erase contents of EEPROM */
eraseEEPROM();
/* Write contents of writeData array to address 180 */
writeEEPROM( 0x1000, writeData, LEN(writeData));
/*
JEDEC Code (working) getting output as per datasheet (0x9F = 159)
SS=0;
SPI1_transfer(159);
x=SPI1_transfer(0);
UART5PutChar(x);
y=SPI1_transfer(0);
UART5PutChar(y);
z=SPI1_transfer(0);
UART5PutChar(z);
*/
while(1)
{
/* Read contents of EEPROM into readData array
* start at address 180 and read up to 180+length(readData) */
readEEPROM( 0x1000, readData, LEN(readData) );
}
} /* END main() */
/*******************************************************************************
* Function Name: SPI1_Init()
********************************************************************************
* Summary:
* SPI1 Initialization
*
* Parameters:
* None.
*
* Return:
* None.
*
*******************************************************************************/
void SPI1_Init(void)
{
/* Configure Peripheral Pin Select (PPS) for the SPI1 module
* Note: SS will be toggled manually in code
* SCK is hardwired to pin 55 */
/* Output Pin Selection */
RPE5R = 8;
SDI1R = 3;
/* RB4 (Slave Select 1) : output */
TRISDbits.TRISD9 = 0;
/* SPI configuration */
/* SPI1CON Register Configuration
* MSTEN: Master Mode Enable bit = 1 (Master)
* CKP (clock polarity control) = 0
* CKE (clock edge control) = 1
* ON: SPI Peripheral On bit
* 8-bit, Master Mode */
SPI1CON = 0x8120;
/* SPI1BRG Register Configuration */
SPI1BRG = 0x4D;
//REFOCONbits.ON = 1;
// REFOCONbits.DIVSWEN = 1;
}
/*******************************************************************************
* Function Name: SPI1_transfer()
********************************************************************************
* Summary:
* Write to and Read from SPI1 buffer
*
* Parameters:
* char b - Writes a Character to Buffer
*
* Return:
* Char - Returns the Character Read from EEPROM
*
*******************************************************************************/
int SPI1_transfer( int b)
{
/* write to buffer for TX */
SPI1BUF = b;
/* wait transfer complete */
while(!SPI1STATbits.SPIRBF);
/* read the received value */
return SPI1BUF;
} /* END SPI1_transfer() */
/*******************************************************************************
* Function Name: waitBusy()
********************************************************************************
* Summary:
* Checks if EEPROM is ready to be modified and waits if not ready
*
* Parameters:
* None.
*
* Return:
* None.
*
*******************************************************************************/
void waitBusy()
{
char status = 0;
do{
/* Select EEPROM */
SS = 0;
/* Read EEPROM status register */
SPI1_transfer(RDSR);
/* send dummy byte to receive incoming data */
status = SPI1_transfer(0);
/* Release EEPROM */
SS = 1;
}
/* write-in-progress while status<0> set to '1' */
while( status & 0x01);
} /* END waitBusy() */
/*******************************************************************************
* Function Name: readEEPROM()
********************************************************************************
* Summary:
* Reads data from EEPROM
*
* Parameters:
* Inputs: address - EEPROM address
* loadArray - array to load EEPROM data to
* loadArray_size - number of bytes of EEPROM data to load into array
*
* Return:
* None.
*
*******************************************************************************/
void readEEPROM( int address, char* loadArray, int loadArray_size)
{
int i;
/* Wait until EEPROM is not busy */
waitBusy();
/* Select EEPROM */
SS = 0;
/* Initiate Read */
SPI1_transfer( READ);
/* Address must be 16-bits but we're transferring it in two 8-bit sessions */
SPI1_transfer( address >> 16);
SPI1_transfer( address >> 8);
SPI1_transfer( address);
/* Request and store loadArray_size number of bytes into loadArray */
for( i=0 ; i<loadArray_size ; i++)
{
/* send dummy byte to read 1 byte */
loadArray[i] = SPI1_transfer( 0x00);
}
/* Release EEPROM */
SS = 1;
/* UART Test */
for(i=0;i<35;i++)
{
UART5PutChar(loadArray[i]);
for(j=0;j<20000;j++)
{}
}
} /* END readEEPROM() */
/*******************************************************************************
* Function Name: writeEEPROM()
********************************************************************************
* Summary:
* Write data to EEPROM
*
* Parameters:
* Inputs: address - EEPROM address
* storeArray - array of which contents are stored in EEPROM
* storeArray_size - number of bytes in array to store into EEPROM
*
* Return:
* None.
*
*******************************************************************************/
void writeEEPROM( int address, char* storeArray, int storeArray_size)
{
int i;
/* Wait until EEPROM is not busy */
waitBusy();
/* Select EEPROM */
SS = 0;
/* Send WRITE_ENABLE command */
SPI1_transfer( WREN);
/* Release EEPROM */
SS = 1;
/* Select EEPROM again after WREN cmd */
SS = 0;
/* Initiate Write */
SPI1_transfer( WRITE);
SPI1_transfer( address >> 16 );
SPI1_transfer( address >> 8 );
SPI1_transfer( address );
/* write 1 byte at a time from array */
/* MSB at lowest address (0 - first letter in string) */
for( i=0 ; i<storeArray_size; i++)
{
/* Initiate Write */
SPI1_transfer( WRITE);
SPI1_transfer( (address+i) >> 16 );
SPI1_transfer( (address+i) >> 8 );
SPI1_transfer( address+i );
SPI1_transfer( storeArray[i]);
}
/* Release EEPROM */
SS = 1;
} /* END writeEEPROM() */
/*******************************************************************************
* Function Name: eraseEEPROM()
********************************************************************************
* Summary:
* Erase entire contents of EEPROM
*
* Parameters:
* None
*
* Return:
* None.
*
*******************************************************************************/
void eraseEEPROM()
{
/* Wait until EEPROM is not busy */
waitBusy();
/* Select EEPROM */
SS = 0;
/* Send WRITE_ENABLE command */
SPI1_transfer( WREN);
/* Release EEPROM */
SS = 1;
/* Select EEPROM again after WREN cmd */
SS = 0;
/* send CHIP_ERASE command */
SPI1_transfer( CE);
/* Release EEPROM */
SS = 1;
} /* END eraseEEPROM() */
/*******************************************************************************
* Function Name: Init_uart()
********************************************g************************************
* Summary:
* Initialize UART4
*
* Parameters:
* None
*
* Return:
* None.
*
*******************************************************************************/
void Init_uart()
{
/* Enable UART */
U5MODEbits.ON = 1 ;
/* set baud rate(9600) */
U5BRG = 521;
/* Set U4STA Register for Enabling tx and rx */
U5STA=0x9400;
}
/*******************************************************************************
* Function Name: UART4PutChar(unsigned char Ch)
********************************************************************************
* Summary:
* Send data from controller to putty GUI
*
* Parameters:
* input
* unsigned char Ch - To Send a byte of data over UART
*
* Return:
* None.
*
*******************************************************************************/
void UART5PutChar(char Ch)
{
while(U5STAbits.UTXBF == 1);
U5TXREG=Ch;
}
/*******************************************************************************
* Function Name: Bitconfig_uart()
********************************************************************************
* Summary:
* UART Pin Configuration
*
* Parameters:
* None
*
* Return:
* None.
*
*******************************************************************************/
void Bitconfig_uart(void)
{
/* UART4 Initialization */
// OSCCON=0x00002200;
/* Set pins as digital */
ANSELBbits.ANSB2 = 0;
ANSELBbits.ANSB0 = 0;
/* Set UART Tx pin as Output */
TRISBbits.TRISB0 = 0; //in controler tx
TRISBbits.TRISB2 = 1; // in controller RX
/* Peripheral Pin select for UART4 */
U5RXR=0x07;
RPB0R=0x04;
}
I faced the same problem for 3 long days until I found that there's a 18bytes long register called Block Protection Register BPR.
You need to set its bits to 0, according to the memory area you want to write.
So I read the BPR (send command 0x72 followed by 18 byte read) and I found it was not at zero everywhere in my case.
Reading on page 41 of the datasheet you can see that after a power on the BPR register is set to 5555 FFFFFFFF FFFFFFFF, so it protects from write the whole memory.
So for testing purpose I tried to clears it completely, and there's a specific command (0x98) for that purpose, allowing you to write anywhere in the whole memory.
But be sure to write enable the memory (command 0x06) before sending the clear BPR command (command 0x98).
At this point if you read the BPR (command 0x72) you will read 00 at every of its 10 bytes. (And this means the whole memory is now writeable)
In this state the write now finally works for me.
(I sent WriteEnable - SectorErase - SectorRead - WriteEnable - SectorWrite - SectorRead and it now works!)
Hope it helps, the datasheet is very chaotic about that.
P.S.
Somewhere the datasheet says that BPR is 18 bytes long, it is wrong, the BPR is only 10 bytes long