STM32 programming – Bit or Byte ‘Banging’ on AD9850

Bit or Byte banging, what is that exactly?!

Sometimes device(s) has no standard serial or parallel protocols as are I2C, SPI and others. Instead, just series of bits or bytes and separate clock. Excellent example is DDS chip AD9850 – we may chose or serial or parallel interfacing. On serial interfacing we using ‘bit banging’ – we put one bit on GPIO port, then on another GPIO port one clock, then next bit on port… until all bites are transferred. Then we send frequency and phase update on third wire, brief pulse 1 then 0. If we want parallel (8 times faster) interfacing, we put whole byte on 8 pins, in our example GPIO A0 to A7, then on another wire we ‘fire’ clock pulse, and after transferring all data, also ‘firing’ update frequency and phase.  Before proceed to our program in Keil, we should to consult our datasheet about AD9850:

Click to access ad9850.pdf

FM radio or Frequency Wobbler

In the codes below, there are two options: FM radio (chose for example 1/3 of the frequency, say 33 MHz, then ‘catch’ third harmonic on 99 MHz, and use comparator for getting almost square wave, so that odd harmonics are stronger), or “Frequency Wobbler”, excellent tool for RLC circuit characterization (testing band pass, low pass, notch and other filters as well as resonant circuits) from 0 to 62.5 MHz with AD9850 – or up to 90 MHz with AD9851, which is really hard to find.  You may change code so that sweep is only upward, and then program one pin before sweep to output short pulse for oscilloscope external trigger. Or leave as is and listen on SDR Software Defined Radio response from RLC circuits.

I made both options available in the same program, just pay attention to GPIOA registers – there are difference in the case of serial and in the case of parallel interfacing. Also, for serial or parallel, there are functions “dds_update_freqS” and “dds_update_freqP”, probably you correctly guessed, ‘P’ is for parallel, ‘S’ is for serial. Now, copy paste this code as usually onto your Keil editor:

		/********************************************************************** 
		 Short but sweet sweep program. It goes from wanted low and high 
		 frequency with desired steps. In this example with parallel mode,
		 it goes 8 times faster than in serial mode. 
		 
		======================Pin map:=======================
		STM32F103C8      AD9850       ST-LINK V2
		GND---------------GND-----------GND
		VCC----------------------------+3.3V
		..................VCC----------+5V
		B1----------------WCLK
		B10---------------FQUP
		B11---------------RESET
		A0----------------D0
		A1----------------D1
		A2----------------D2
		A3----------------D3
		A4----------------D4
		A5----------------D5
		A6----------------D6
		A7----------------D7
		======================================================
		This example is free to use, share modify... do what you want. :D
		*******************************************************************/

#include "stm32f10x.h"

uint8_t phase = 0;
int    analog = 0;
//in the case of sweep function:
int sweep_begin = 0;
int sweep_end   = 0;
int sweep_step  = 0;
//in the case of FM radio:
float freq= 26e6;    // "Intended" frequency (33e6= 33 000 000 Hz, or 33 MHz), but:
float	offset= 49.5e3; // Since ADC is directly connected to analog input, it has some non-zero voltage. 
	               // This voltage should be ideally VCC/2, or 3.3V/2= 1.65V, but it is not always true.
	               // So, offset should be subtracted from intended frequency so that final frequency is where we want.
	               // Set this number zero, then look at your receiver (RTL SDR, for example), how much it goes up, 
	               // then set this offset. This number is subtracted inside update (in IRQ handler function).
	      			   // In my case, it is 49.0 KHz above, so positive value will be calculated inside IRQ thing (freq-offset)

void delay(long cycles)
{
  while(cycles >0)
  cycles--; // Some stupid delay, it is not in milliseconds or microseconds, but rather in some 'wasted clock cycles'
}

void ADC_enable(void)
{
	RCC->CFGR |= RCC_CFGR_ADCPRE_DIV6;// ADC clock = 12 MHz, maximum is 14, but there is no divider for that freq (72MHz / 6 = 12MHz). 
	RCC->APB2ENR |= RCC_APB2ENR_ADC1EN | RCC_APB2ENR_AFIOEN; //enabling ADC clock, interrupt enable, 
	//while clock for port A and B is enabled down below

	ADC1->CR1 |=ADC_CR1_EOCIE;   //ADC interrupt enabled
	NVIC_EnableIRQ(ADC1_2_IRQn); //interrupt enabled
	
	ADC1->SMPR2 |= ADC_SMPR2_SMP8_0|ADC_SMPR2_SMP8_1|ADC_SMPR2_SMP8_2;
	ADC1->SQR3 |= ADC_SQR3_SQ1_3; //for B0 in sequence 1, channel 8, it is 0b1000 = 8 (IN8)
	//ADC1->SQR3 |=8; // alternative way of setting the same thing as above

	ADC1->CR2 &= ~ADC_CR2_ALIGN; //data is right aligned (0bxxxx111111111111)

	ADC1->CR2 |= ADC_CR2_ADON | ADC_CR2_CONT; //ADC converter is on
	delay(1000); //alow ADC to stabilize - 1 mS, but my delay is not exactly 1 mS, it is much shorter...
    ADC1->CR2 |= ADC_CR2_CAL;
	delay(1000); //it is better to leave some time, just few clock cycles...
	ADC1->CR2 |= ADC_CR2_ADON; //not sure it requires to call it again?
	delay(1000); //After first ADON, ADC is just set, then second time ADC is actually enabled
}

void gpio_A_and_B_port_enable(void)
{
	RCC->APB2ENR |= RCC_APB2ENR_IOPAEN | RCC_APB2ENR_IOPBEN; //ports A & B clock enabled
	/* For parallel connection: */
	//GPIOA->CRL = 0x33333333; //for parallel - pins A0 to A7 are used, 50 MHz, push-pull
	/* For serial connection: */
	GPIOA->CRL = 0x34444444; //for serial, only pin A7 is used, other pins MUST be floating
	GPIOB->CRL = 0x44444430; //Pin B0 is analog input, pin B1 is digital output, 50 MHz, push-pull
	GPIOB->CRH = 0x44443344; //Pins B10 and B11 are digital putput, 50 MHz, push-pull
}

void reset_d(void)
{
	GPIOB->BSRR = GPIO_BSRR_BS11; // Reset, pin B11
  GPIOB->BSRR = GPIO_BSRR_BR11;
}

void clock_d(void)
{
	GPIOB->BSRR = GPIO_BSRR_BS1;  // Clock, pin B1
	GPIOB->BSRR = GPIO_BSRR_BR1;
}

void update_d(void)
{
	GPIOB->BSRR = GPIO_BSRR_BS10; // Update, pin B10
	GPIOB->BSRR = GPIO_BSRR_BR10;
}


void dds_reset(void)
{
	// Set everything low first
	GPIOB->BRR = GPIO_BRR_BR1|GPIO_BRR_BR10|GPIO_BRR_BR11; //instead BSRR, we use BRR, Bit Reset Retister
	reset_d();  // Pulse reset
	clock_d();  // Pulse clock
	update_d(); // Pulse load
}

void dds_writeParallel(uint8_t byte)
{
	GPIOA->ODR = byte;
	clock_d();
}

void dds_writeSerial(uint8_t byte)
{
  uint8_t i;
  uint8_t bit;
  for(i = 0; i < 8; i++) 
	{
      bit = ((byte >> i) & 1);
      if(bit == 1)
         GPIOA->BSRR = GPIO_BSRR_BS7; // Data bit set on pin A7
      else
         GPIOA->BSRR = GPIO_BSRR_BR7; //data bit reset (A7)
         clock_d();
  }
}

/* Parallel updating frequency - different than serial */
void dds_update_freqP(float freq)
{
    uint32_t tuning_word = (freq * 34.36426); // resolution is 0.0291 Hz, so 1/0.0291 = 34.36426 steps per 1 Hz
	/* Another chip, AD9851 has almost the same properties. Just different resolution + ability to use low frequency
	   oscillator by enabling internal multiplier x6 on first word W0, which should be: 0b00000010 */
	dds_writeParallel(((uint8_t)0b00000000) & 0xFF); // 0b00000100 = W0* - power off - should be phase + pwr_down + control bits
	//0bxxxxx, five upper bits for phase, 180/90/45/22.5/11.25 degrees, then one bit for power down (if set), and two zeroes (reserved)
	dds_writeParallel((tuning_word >> 24) & 0xFF);
	dds_writeParallel((tuning_word >> 16) & 0xFF);
	dds_writeParallel((tuning_word >> 8) & 0xFF);
	dds_writeParallel(tuning_word & 0xFF);
	update_d();// Load (f_upd)
	// *-> in parallel mode, it is possible to send only W0 for changing phase and power up/down.
}

/* Serial updating frequency - different than in parallel */
void dds_update_freqS(float freq)
{
	// Updates DDS output frequency. Supply frequency in Hz.
	uint32_t tuning_word = (freq * 34.36426); // resolution is 0.0291 Hz, so 1/0.0291 = 34.36426 steps per 1 Hz
	dds_writeSerial(tuning_word & 0xFF);
	dds_writeSerial((tuning_word >> 8) & 0xFF);
	dds_writeSerial((tuning_word >> 16) & 0xFF);
	dds_writeSerial((tuning_word >> 24) & 0xFF);
	dds_writeSerial(0b00000000); // 0b00000100 = power off
	update_d(); // this function finally send signal to AD9850 to update frequency and phase
}

void sweep(int sweep_begin, int sweep_end, int sweep_step)
{
	for (int i=sweep_begin;i<sweep_end;i+=sweep_step)
		{
			dds_update_freqS(i);
			//delay(50); //if you want slow up upward sweeping
		}
		//now going back. If you want only one way (up), then remove or comment (/**/) for loop below for only down,
		//do the same with for loop above. 
		for (int i=sweep_end;i>sweep_begin;i-=sweep_step)
		{
			dds_update_freqS(i);
			//delay(50); //if you want to slow down sweeping downward
		} 
}

void ADC1_2_IRQHandler(void)
{
	  if (ADC1->SR & ADC_SR_EOC) 
	{
		analog=ADC1->DR;
		dds_update_freqS((freq-offset)+(analog*26)); //FM modulation. No multiplier for NFM, but for WFM it is an*26 or so...
	}
} 

int main()
{
	gpio_A_and_B_port_enable();	
	dds_reset(); 
	ADC_enable();

  while (1) 
  {
	  //sweep(25e6,26e6,1e3); //frequency begin, frequency end, step size
  }
}

STM programming ADC and true DAC

True DAC or PWM dac?!

Depends of which board we have. If chip is STM32f103c8, then there is no DAC on it, but we can mimic DAC by using PWM. If board has stm32f103vet6 on the other hand, it has DAC and we can  use both channels as stereo.  Please watch video first, then it will be clear why we need move SPI pins with AFIO_MAPR function to another place – both shares the same pins.

#include "stm32f10x.h"
#include "printMsg.h"
#include "delayUs.h"
#include "adc.h"
#include "dac.h"
#include "spi.h"
#include "sample.h"
#include "pwm_as_dac.h"

int main(void)
{
	usart_1_enable();
	timer2enablePWM();
	spiEnable();
	adcEnable(); 
	dacEnable(); 
	//setModule(433.120,0); // (frequency in MHz, power in steps from 0 to 7, or 1.26 mW to 100 mW)
	
	while(1) 
	{
		//adc();
		
		for (int i=0;i<raw;i++)
		{
			PWMdac(rawData[i]/4,rawData[i]/4); //since our PWM DAC imitation has only 8 bit resolution, we need to divide 4096 / 4
			dac(rawData[i]*10-2048,rawData[i]*10-2048); //8 bits to 12 bits resolution, but it may be needed to amplify by multiplying *10 and offset -2400
			delay(330);
		}
		dac(left,right); //normal DAC, if inputs are 12 bits, the output is also 12 bit
		delay(50000000); //long delay between two plays
	}
	
}
#include "stm32f10x.h"
#include "delayUs.h"
#include "adc.h"
#include "dac.h"

int left=0;
int right=0;

void adcEnable(void)
{
	RCC->APB2ENR |= RCC_APB2ENR_IOPBEN | RCC_APB2ENR_ADC1EN |RCC_APB2ENR_ADC2EN | RCC_APB2ENR_AFIOEN; //enabling ADC clock, interrupt enable, 
	RCC->CFGR |= RCC_CFGR_ADCPRE_DIV6;// ADC clock = 12 MHz, maximum is 14, but there is no divider for that freq (72MHz / 6 = 12MHz). works with div6 too
	//while clock for port A and B is enabled down below
	// pin B0 is analog input, no need special GPIO setting
	// pin B1 is analog input, no need special GPIO setting
	
	ADC1->CR1 |=ADC_CR1_EOCIE;   //ADC interrupt enabled
	ADC2->CR1 |=ADC_CR1_EOCIE;   //ADC interrupt enabled
	//NVIC_EnableIRQ(ADC1_2_IRQn); //interrupt enabled
	
	ADC1->SMPR2 |= ADC_SMPR2_SMP8_0;//|ADC_SMPR2_SMP8_1|ADC_SMPR2_SMP8_2;
	ADC2->SMPR2 |= ADC_SMPR2_SMP8_0;//|ADC_SMPR2_SMP8_1|ADC_SMPR2_SMP8_2;

	ADC1->SQR3 |=8; //L B0
  ADC2->SQR3 |=9; //R B1
	ADC1->CR2 &= ~ADC_CR2_ALIGN; //data is right aligned (0bxxxx111111111111)
	ADC2->CR2 &= ~ADC_CR2_ALIGN; 

	ADC1->CR2 |= ADC_CR2_ADON | ADC_CR2_CONT; //ADC converter is on
	ADC2->CR2 |= ADC_CR2_ADON | ADC_CR2_CONT;
	delay(1000); //alow ADC to stabilize - 1 mS, but my delay is not exactly 1 mS, it is much shorter...
  ADC1->CR2 |= ADC_CR2_CAL;
	ADC2->CR2 |= ADC_CR2_CAL;
	delay(1000); //it is better to leave some time, just few clock cycles...
	ADC1->CR2 |= ADC_CR2_ADON; //not sure it requires to call it again?
	ADC2->CR2 |= ADC_CR2_ADON; 
	delay(1000); //After first ADON, ADC is just set, then second time ADC is actually enabled
}

/* For enabling IRQ, uncomment three lines above */
void ADC1_2_IRQHandler(void)
{ 
    left=ADC1->DR;
		right=ADC2->DR;
} 

/* Manual call of the ADC conversion channels */
void adc(void)
{
	ADC1->CR2 |=ADC_CR2_SWSTART;
	ADC2->CR2 |=ADC_CR2_SWSTART;
	left=ADC1->DR;
  right=ADC2->DR;
}
#ifndef adc_h
#define adc_h

extern int left;
extern int right;

void adcEnable(void);
void adc(void);

#endif
#include "stm32f10x.h"
#include "printMsg.h"
#include "delayUs.h"

void dacEnable(void)
{
	
	RCC->CFGR |= RCC_CFGR_PPRE1_DIV2;// trying to divide clock by 2 for APB1, for max freq of 36 MHz
	RCC->APB1ENR |= RCC_APB1ENR_DACEN; //DAC interface clock enable
	RCC->APB2ENR |= RCC_APB2ENR_IOPAEN;
		
	DAC->CR |= DAC_CR_BOFF1|DAC_CR_BOFF2; //DAC buffer
	//DAC->CR |= DAC_CR_WAVE2_1|DAC_CR_WAVE2_0|DAC_CR_WAVE1_1|DAC_CR_WAVE1_0;
	//DAC->CR |= DAC_CR_MAMP1_3|DAC_CR_MAMP2_1|DAC_CR_MAMP1_1|DAC_CR_MAMP1_0; //maximum aplitude?
	//DAC->CR |= DAC_CR_MAMP2_3|DAC_CR_MAMP2_2|DAC_CR_MAMP2_1|DAC_CR_MAMP2_0; //maximum aplitude?
	DAC->CR |= DAC_CR_TSEL1_0|DAC_CR_TSEL1_1|DAC_CR_TSEL1_2; //software trigger 0b111
  DAC->CR |= DAC_CR_TSEL2_0|DAC_CR_TSEL2_1|DAC_CR_TSEL2_2; //software trigger 0b111
	DAC->CR |= DAC_CR_TEN1|DAC_CR_EN1; //software trigger for DAC1 enable, DAC1 enable
	DAC->CR |= DAC_CR_TEN2|DAC_CR_EN2; //software trigger for DAC2 enable, DAC2 enable
}

void dac(int left, int right)
{
	DAC->SWTRIGR |= DAC_SWTRIGR_SWTRIG1;
	DAC->SWTRIGR |= DAC_SWTRIGR_SWTRIG2; //not sure which trigger, so both...
	DAC->DHR12R1 = left; //currently left channel, pin A4
	DAC->DHR12R2 = right; //currently right channel, pin A5
}
#ifndef dac_h
#define dac_h

extern int audio;
void dacEnable(void);
void dac(int left,int right);

#endif
#include "stm32f10x.h"
#include "adc.h"

void timer2enablePWM(void)
{
	RCC->APB2ENR |= RCC_APB2ENR_IOPAEN | RCC_APB2ENR_AFIOEN; //port B clock enabled (3), port A clock enable (2), Alternate IO clock enable (0)
	RCC->APB1ENR |= RCC_APB1ENR_TIM2EN; //timer 2 clock enable (2)
	
	GPIOA->CRL |= GPIO_CRL_CNF0_1|GPIO_CRL_MODE0_0|GPIO_CRL_MODE0_1;
	GPIOA->CRL &= ~(GPIO_CRL_CNF0_0);  //PA0
	
  GPIOA->CRL |= GPIO_CRL_CNF1_1|GPIO_CRL_MODE1_0|GPIO_CRL_MODE1_1;
	GPIOA->CRL &= ~(GPIO_CRL_CNF1_0); //PA1
	
  TIM2->CCER |= TIM_CCER_CC1E; //capture/compare timer1 output enable
	TIM2->CCER |= TIM_CCER_CC2E; //capture/compare timer2 output enable
	
	TIM2->CR1 |= TIM_CR1_ARPE; //auto reload preload enable TIMxARR is buffered
	TIM2->CCMR1 |= TIM_CCMR1_OC2M_1 | TIM_CCMR1_OC2M_2 | TIM_CCMR1_OC2PE; //output compare 2 mode 0b110 (14:12)?, output compare 2 preload enable
	TIM2->CCMR1 |= TIM_CCMR1_OC1M_1 | TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1PE;
	
	
	//PWM freq = Fclk/PSC/ARR  72MHz/1000
	//PWM Duty = CCR1/ARR
	TIM2->PSC = 0; //prescaler value, 72 MHz divided by:
	TIM2->ARR = 1024; //auto reload register, value of 1024 with prescaler value 0 result in PWM frequency of 70 kHz
	//TIM2->CCR1= 512; //first of two channels
	//TIM2->CCR2= 512; //capture/compare value, duty cycle (disabled here, enabling in call function in DSP_1.c)
	TIM2->EGR |= TIM_EGR_UG; //update generation, re-initialize
	TIM2->CR1 |= TIM_CR1_CEN; //counter enabled
}

void PWMdac(int left, int right)
{
	TIM2->CCR1 = left;  //duty cycle
	TIM2->CCR2 = right; //duty cycle
}
#ifndef pwm_as_dac_h
#define pwm_as_dac_h

void timer2enablePWM(void);
void PWMdac(int left,int right);

#endif
/* This software is provided by https://wildlab.org and
   Milan Karakas from Croatia. This is free program, but 
	 also "beerware". This means if you want this beta test
	 phase to grow into something really great, please consider 
	 some donation here: 
	 https://www.paypal.me/milankarakas?locale.x=en_US
	 It is still in beta test phase, and will be upgraded. 
	 So far it works at 433.120 MHz, and you need to change 
	 the frequency if you wish to something else - in library
	 'Si4432.c', there is math and you should to calculate 
	 and change values of the register for other frequencies. 
	 Out there exist also Si4432 - 868 MHz module, and this 
	 program works with this one too, but then you MUST change
	 the frequency, else output TX amplifier may burn. 
	 Later, will ad my own math to do that, but since it is still
	 in beta testing phase... stay tuned.
*/

#include "stm32f10x.h"

void spiEnable(void)
{
	RCC->APB2ENR |= RCC_APB2ENR_IOPAEN|RCC_APB2ENR_IOPBEN|RCC_APB2ENR_AFIOEN; //already exist, but anyway...
	/* Remapping SPI pins */
	AFIO->MAPR |=AFIO_MAPR_SWJ_CFG_1; //first we should to enable afio clock (above), then this one "JTAG-DP Disabled and SW-DP Enabled", releasing PA4 and PA5
	AFIO->MAPR |=AFIO_MAPR_SWJ_CFG_0|AFIO_MAPR_SPI1_REMAP; //moving SPI1 from PA4/PA5/PA6/PA7 to PA15/PB3/PB4/PB5 (PA15=NSS, PB3=SCK, PB4=MISO, PB5=MOSI
	
	/* GPIO pin A15 (was A4) is NSS ("Not" Slave Sellect), inverted... if low (0), then it is selected */
	GPIOA->CRH |= GPIO_CRH_CNF15_1|GPIO_CRH_MODE15_0|GPIO_CRH_MODE15_1;// 50 MHz - NSS (nSEL on Si4432)
	GPIOA->CRH &= ~GPIO_CRH_CNF15_0; //alternate function PP, this A4->moved to A15 pin must be high with external resistor 3kOhm to 4.7kOhm
	/* GPIO pin B3 (was A5) is SPI clock SCK */
	GPIOB->CRL |= GPIO_CRL_CNF3_1|GPIO_CRL_MODE3_0|GPIO_CRL_MODE3_1;// 50 mhz - SCK A5->moved to B3
	GPIOB->CRL &= ~GPIO_CRL_CNF3_0; //alternate function PP
	/* GPIO pin B4 (was A6) is MISO */
	GPIOB->CRL &= ~(GPIO_CRL_MODE4_0|GPIO_CRL_MODE4_1); // INPUT - MISO, A6->moved to B4
	GPIOB->CRL |= GPIO_CRL_CNF4_0;
		
	/* GPIO pin B5 (was A7) is MOSI */
	GPIOB->CRL |= GPIO_CRL_CNF5_1|GPIO_CRL_MODE5_0|GPIO_CRL_MODE5_1;// 50 MHz - MOSI, A7->moved to B5
	GPIOB->CRL &= ~GPIO_CRL_CNF5_0; //alternate function PP
	
	/*  Configuring SPI */
	RCC->APB2ENR |= RCC_APB2ENR_SPI1EN;// SPI enable
	SPI1->CR1 |= SPI_CR1_BR_2;//|SPI_CR1_BR_1;//|SPI_CR1_BR_1|SPI_CR1_BR_0; // 72MHz/?
	SPI1->CR1 &= ~(SPI_CR1_CPOL|SPI_CR1_CPHA|SPI_CR1_DFF); // modes, 0 for polarity, and 0 for iddle clock=0, dff=0 (8 bit), lsbfirst=0 (MSB first), *
	SPI1->CR2 |= SPI_CR2_SSOE; //NSS enabled         
	SPI1->CR1 |= SPI_CR1_MSTR;// master configuration  
}

void spiWrite(int reg, int cmd)
{
  SPI1->CR1 |= SPI_CR1_SPE;
	SPI1->DR = (0x80|reg); //usually 0x80 does not belongs to SPI, but here it is "command mode", specific for Si4432
	while (!(SPI1->SR & SPI_SR_TXE)){}; 
	SPI1->DR = cmd; 
	while (!(SPI1->SR &SPI_SR_TXE)){}; 
	while(SPI1->SR & SPI_SR_BSY);
	while (!(SPI1->SR & SPI_SR_OVR)){}; //if single byte is sent,...
  SPI1->CR1 &= ~SPI_CR1_SPE;
}

int spiRead(int reg)
{
	SPI1->CR1 |= SPI_CR1_SPE;
	SPI1->DR =reg;
	while (!(SPI1->SR & SPI_SR_TXE)){};
	while(SPI1->SR & SPI_SR_BSY){}; //waiting little bit longer between two sendings
  SPI1->DR = 0xFF; //dummy byte
	while (!(SPI1->SR & SPI_SR_RXNE)){};
	int rd=SPI1->DR; //dummy read? Whole thing does not working properly without
	while (!(SPI1->SR & SPI_SR_RXNE)){};
  int r=SPI1->DR;
	SPI1->CR1 &= ~SPI_CR1_SPE;
	return r;
}
#ifndef spi_h
#define spi_h

extern void spiEnable(void);
extern void spiWrite(int reg, int cmd);
extern int spiRead(int reg);

#endif

Sorry, but last file “sample.h” is too long for this page, so it is in separate window (just select all, copy and paste into your sample.h file:  sample

Logic analyzer – do we need it?

Logic analyzer and its use

When programming any MCU, no matter Arduino IDE, Keil, Atmel studio or other compilers and assemblers, many times we got intro problem not knowing what happening on our data transfer from and to MCU. For example, we want to use I2C protocol for communicating with some sensor, but it does not respond. Many things can be wrong, and without logic analyzer, we just don’t know whether our code is wrong, the sensor is broken, or maybe something else.

Cheap Chinese clone or professional one?

Good question, depend of many factors. Do you use it for your work, or do you program for fun? I am using for my personal projects, and this one that cost less than $50 US.:

analyzer

It works fine, but there is limit in speed, especially with more than one channel. It is USB 2.0 product and has no analog part as it has original Saleae Logic analyzer. It is too much expensive for my pocket, especially because I am not professional. I just have dream that it will be mine one day, but until then… Anyway, here is video for anyone who are interested and does not know what I am talking about:

Recently I had problem programming STM32 and connecting OLED display. Despite spending hours googling what exact command should be implemented, and reading their documentation, I was not able to get picture on the OLED display. Then got idea – programmed Atmega 328p with Arduino example, then put logic analyzer to I2C bus, and got the codes for initialization of the display.

Another example is when I wanted to know toy grade quadcopters, how transmitter and receiver know where to ‘jump’ by using ‘frequency hopping’. Using SPI protocol and Logic analyzer, I was able to see exactly what is ‘the secret’. Aside many bytes that transmitter sending for moving flying device up/down, left and right, there is one byte that constantly changes even when remote sticks are still – that is information for next channel. So, TX sending information on current channel, then last bit is channel number for next transmission. Whole protocol is made so that if it goes briefly out of range, or missing one packet due to noise, receiver back to original ‘calling’ channel, and in the same time transmitter sending on this channel periodically next possible channel where will be next time. That is so cool to know.

STM32 example of DSP, ADC and DAC

DSP possible on small MCU?

Yes, DSP (Digital Signal Processing) is possible with some speed limitations. For example, if FIR filter (Finite Impulse Response) has too much taps, whole loop process will be slow, and sampling ratio depends strongly of number of those elements. Out there exist specialized MCUs with additional hardware for floating point calculation (FPU), but our STM 32 or whatever MCU you are using, can do DSP.

First, we need to find some math to calculate ‘taps’, you may use your GNU radio companion for that, or some free online calculators as is this one (really simple): http://t-filter.engineerjs.com/

Just set parameter of wanted frequency filtering, and on the right side you have two choices: plain text or C/C++ code. Chose code and copy/paste into my codes in ‘coefficients.h’ file, replacing old ones (or just comment old one with ‘//’. Change “static double filter_taps[FILTER_TAP_NUM] = {…” into “static const float taps[] = {….”, that is because it is intended for PC and other high frequency CPUs instead our MCUs. Name in ‘[]’ square brackets is defined above by “#define FILTER_TAP_NUM”, so leave those brackets empty, else compiler may complain about re-definition.

The codes:

#include "stm32f10x.h"
#include "coefficients.h"
#include "pwm_as_dac.h"
#include "adc.h"

float y=0.0;
int x[FILTER_TAP_NUM ];
int adc_value=0;

int main(void)
{
	ADCenable();
	timer2enablePWM();

	while(1)
	{
		y=0;
		for(uint16_t i=0;i<FILTER_TAP_NUM ;i++)
		{
			y=y+x[i]*taps[FILTER_TAP_NUM  - i - 1];
		}
		for(uint16_t i=0;i<FILTER_TAP_NUM -1;i++)
		{
			x[i]= x[i+1];
		}
		x[FILTER_TAP_NUM -1]= adc();

		dac((int)y/4-200);
	}
}
#ifndef coeficients_h
#define coeficients_h

// Define FILTER_TAP_NUM 33	
//static const float h[] = {4.684409422081195e-18, -0.005663635209202766, 6.734740765645466e-18, 0.011587434448301792, -1.2573590333975574e-17, -0.02472740039229393, 2.1312048747716416e-17, 0.04784134402871132, -3.1619763082060183e-17, -0.08602967858314514, 4.1927475762042725e-17, 0.15215569734573364, -5.0665930867061117e-17, -0.2940477132797241, 5.650478043539123e-17, 0.9478252530097961, 1.502117395401001, 0.9478252530097961, 5.650478043539123e-17, -0.2940477132797241, -5.0665930867061117e-17, 0.15215569734573364, 4.1927475762042725e-17, -0.08602967858314514, -3.1619763082060183e-17, 0.04784134402871132, 2.1312048747716416e-17, -0.02472740039229393, -1.2573590333975574e-17, 0.011587434448301792, 6.734740765645466e-18, -0.005663635209202766, -4.684409422081195e-18};	
	
//Define FILTER_TAP_NUM 33	
//static const float h[] = {8.712546657581782e-25, -0.0002239293826278299, 8.553268804612164e-19, 0.0025619769003242254, -3.885060542008433e-18, -0.009687605313956738, 1.0061897762988933e-17, 0.026369733735919, -1.98794331381399e-17, -0.06051621213555336, 3.243698113131562e-17, 0.12741217017173767, -4.522882306991331e-17, -0.2757503390312195, 5.4873560415101953e-17, 0.9398812055587769, 1.4999059438705444, 0.9398812055587769, 5.4873560415101953e-17, -0.2757503092288971, -4.522882306991331e-17, 0.12741221487522125, 3.243699105748297e-17, -0.06051621213555336, -1.987942982941745e-17, 0.02636972814798355, 1.006189693580832e-17, -0.009687609039247036, -3.8850630235502704e-18, 0.002561978530138731, 8.553270355575813e-19, -0.000223929833737202, 8.712546657581782e-25};	

	
/*

FIR filter designed with
http://t-filter.appspot.com

sampling frequency: 10000 Hz

* 0 Hz - 2700 Hz
  gain = 1
  desired ripple = 5 dB
  actual ripple = 3.9012411972242793 dB

* 3000 Hz - 5000 Hz
  gain = 0
  desired attenuation = -40 dB
  actual attenuation = -40.57030203503276 dB

*/

#define FILTER_TAP_NUM 35

static const float taps[] = {
  0.02414625111688885,
  0.06401728741588443,
  0.044933153881769605,
  -0.015681240139849045,
  -0.026149104235903296,
  0.021462665496812958,
  0.016109456391146398,
  -0.02947270429340234,
  -0.005886666419813914,
  0.03886200531313775,
  -0.010072111405837416,
  -0.04736804280493483,
  0.03610926485566697,
  0.05442550241090494,
  -0.08860251029391766,
  -0.058971910009376544,
  0.3122893416422745,
  0.5605715308468502,
  0.3122893416422745,
  -0.058971910009376544,
  -0.08860251029391766,
  0.05442550241090494,
  0.03610926485566697,
  -0.04736804280493483,
  -0.010072111405837416,
  0.03886200531313775,
  -0.005886666419813914,
  -0.02947270429340234,
  0.016109456391146398,
  0.021462665496812958,
  -0.026149104235903296,
  -0.015681240139849045,
  0.044933153881769605,
  0.06401728741588443,
  0.02414625111688885
};

	
#endif
#include "stm32f10x.h"
#include "delayUs.h"
#include "adc.h"

void ADCenable(void)
{
	RCC->APB2ENR |= RCC_APB2ENR_IOPBEN | RCC_APB2ENR_ADC1EN | RCC_APB2ENR_AFIOEN; //enabling ADC clock, interrupt enable, 
	RCC->CFGR |= RCC_CFGR_ADCPRE_DIV4;// ADC clock = 12 MHz, maximum is 14, but there is no divider for that freq (72MHz / 6 = 12MHz). works with div6 too
	//while clock for port A and B is enabled down below
	GPIOB->CRL &= ~(GPIO_CRL_CNF0_0|GPIO_CRL_CNF0_1|GPIO_CRL_MODE0_0|GPIO_CRL_MODE0_1); // pin A0 is analog input
	

	//ADC1->CR1 |=ADC_CR1_EOCIE;   //ADC interrupt enabled
	//NVIC_EnableIRQ(ADC1_2_IRQn); //interrupt enabled
	
	//ADC1->SMPR2 |= ADC_SMPR2_SMP8_0;//|ADC_SMPR2_SMP8_1|ADC_SMPR2_SMP8_2;
	ADC1->SQR3 |= ADC_SQR3_SQ1_3; //for B0 in sequence 1, channel 8, it is 0b1000 = 8 (IN8)
	//ADC1->SQR3 |=8; // alternative way of setting the same thing as above

	ADC1->CR2 &= ~ADC_CR2_ALIGN; //data is right aligned (0bxxxx111111111111)

	ADC1->CR2 |= ADC_CR2_ADON | ADC_CR2_CONT; //ADC converter is on
	delay(1000); //alow ADC to stabilize - 1 mS, but my delay is not exactly 1 mS, it is much shorter...
  ADC1->CR2 |= ADC_CR2_CAL;
	delay(1000); //it is better to leave some time, just few clock cycles...
	ADC1->CR2 |= ADC_CR2_ADON; //not sure it requires to call it again?
	delay(1000); //After first ADON, ADC is just set, then second time ADC is actually enabled
}

/* For some unknown reason, DSP does not work if algorithm is included into IRQ handler, so NVIC is disabled for this IRQ */
void ADC1_2_IRQHandler(void)
{ 
	  if (ADC1->SR & ADC_SR_EOC) 
	{
    adc_value=ADC1->DR;
  }	
} 


int adc(void)
{
	int adc=0;
	ADC1->CR2 |=ADC_CR2_SWSTART;
	//if(ADC1->SR & ADC_SR_EOC)
	while(!(ADC1->SR & ADC_SR_EOC));
	adc=ADC1->DR;
	return adc;
}
#ifndef adc_h
#define adc_h

extern int adc_value;

void ADCenable(void);
int adc(void);

#endif
#include "stm32f10x.h"

void timer2enablePWM(void)
{
	RCC->APB2ENR |= RCC_APB2ENR_IOPAEN | RCC_APB2ENR_AFIOEN; //port B clock enabled (3), port A clock enable (2), Alternate IO clock enable (0)
	RCC->APB1ENR |= RCC_APB1ENR_TIM2EN; //timer 2 clock enable (2)
	
	GPIOA->CRL |= GPIO_CRL_CNF1_1|GPIO_CRL_MODE1_0|GPIO_CRL_MODE1_1;
	GPIOA->CRL &= ~(GPIO_CRL_CNF1_0);
	
  TIM2->CCER |= TIM_CCER_CC2E; //capture/compare timer2 output enable
	TIM2->CR1 |= TIM_CR1_ARPE; //auto reload preload enable TIMxARR is buffered
	TIM2->CCMR1 |= TIM_CCMR1_OC2M_1 | TIM_CCMR1_OC2M_2 | TIM_CCMR1_OC2PE; //output compare 2 mode 0b110 (14:12)?, output compare 2 preload enable
	
	
	//PWM freq = Fclk/PSC/ARR  72MHz/1000
	//PWM Duty = CCR1/ARR
	TIM2->PSC = 0; //prescaler value, 72 MHz divided by:
	TIM2->ARR = 1024; //auto reload register, value of 1024 with prescaler value 0 result in PWM frequency of 70 kHz
	//TIM2->CCR2= 512; //capture/compare value, duty cycle (disabled here, enabling in call function in DSP_1.c)
	TIM2->EGR |= TIM_EGR_UG; //update generation, re-initialize
	TIM2->CR1 |= TIM_CR1_CEN; //counter enabled
}

void dac(int value)
{
	TIM2->CCR2 = value; //here we update capture/compare value for duty cycle
}
#ifndef pwm_as_dac_h
#define pwm_as_dac_h

void timer2enablePWM(void);
void dac(int value);

#endif

 

STM32 programming SPI for Si4432 transceiver

Si4432 transceiver

Using FTDI as power source

Before anything, if you are using STM32 with ST-Link, then MCU and Si4432 is powered by ST-Link. When done with programming, you can use USB FTDI adapter as power source for 3.3V, but first move jumper from 5V to 3.3V (!). Else you can damage both, MCU and SI4432. On block diagram, this wire connection is not shown for reason that some FTDI adapter has voltage selection on bottom side, then you need to solder jumper pads to 3.3V. Here is picture with recommended setting for FTDI for use on your computer and for powering MCU with Si4432:

FTDI

Si4432

To get it working properly, when typing into console, console should be able to send LF and/OR CR symbol (decimal 10 or 13), so rather use HTerm, it is free for Windows and Linux. Do not use both CR and LF (CR-LF), else one of those may be sent over the radio and at receiving site one may notice moving text two rows instead one. Here is screenshot:

HTerm

Default setting in ‘printMsg.c’ is 115200 baud, but you can change to your value, just comment with ‘//’ this one and un-comment (remove ‘//’) one that is the best for you. If you chose less than 9600, then whole thing will be slower than transceiver. In HTerm, there is window with COM port, if it is already open, it will NOT refresh automatically new COM port, you need to click on ‘R’ button next to window with COM port names. Enable “Newline at” and chose LF, you may disable “Show newline characters”.

Codes for remote controller

The codes below is for remote terminal, for communication between two points at fixed frequency and fixer data rate in bauds. For remote controller, the code must be modified. I will do that too, but not sure how soon. If you want it sooner, please buy me a beer. 😀  Just because I have many things to do at once, and sometimes long time may pass between page update. This will kick me to do more.

Codes:

/* This software is provided by https://wildlab.org and
   Milan Karakas from Croatia. This is free program, but 
	 also "beerware". This means if you want this beta test
	 phase to grow into something really great, please buy
	 me a beer :) https://www.paypal.me/milankarakas?locale.x=en_US
	 It is still in beta test phase, and will be upgraded. 
	 BE EXTREMELY CAREFUL WITH FREQUENCY AND POWER !!!
   Your module may be damaged if not made for specific freq
   range. For example, 433 MHz modules from eBay may work
   from say 400 - 440 MHz, but not outside that range. Also
   other modules (315 MHz, 868 Mhz) works with close range. 
   This is because each module has different output low pass
   filter, and phase shifter for the receiver. Transmitter may burn
   if wrong frequency, and receiver may be insensitive due to
   wrong phase on differential inputs. I warned you !!!
   Also, DO NOT use small spring-looking antena that comes
   with the module - this is pure crap. For 433 MHz use for
   example 17 cm wire, or better solder proper coaxial cable
   and proper antenna. Good antenna gives more range than power.	 
	 Later, will ad my own math to do that, but since it is still
	 in beta testing phase... stay tuned.
*/

#include "stm32f10x.h"
#include "printMsg.h"
#include "delayUs.h"
//#include "string.h"
#include "spi.h"
#include "si4432.h"

int len=0;

int main()
{
	usart_1_enable(); //enabling serial protocol
	spiEnable(); //enabling SPI protocol
	
	/* Be careful with the frequency of your module, and power !!! */
	setModule(433.120,0); // (frequency in MHz, power in steps from 0 to 7, or 1.26 mW to 100 mW)
	//enabling and initializating Si4432, setting IRQ for USART, 
	//setting freq (240.001-959.999 MHz), not a Hz outside (!)
  //Output power: 
	/*
	  0 = +1  dBm =  1.26 mW
	  1 = +2  dBm =  1.58 mW
	  2 = +5  dBm =  3.16 mW
	  3 = +8  dBm =  6.31 mW
	  4 = +11 dBm = 12,59 mW
	  5 = +14 dBm = 25.12 mW
	  6 = +17 dBm = 50.12 mW
	  7 = +20 dBm = 100 mW (!)
	(modem baud rate is 9600, I did not finish calculations for that, and other parameters as is type of modulation...)
	(modem currently works in (G)FSK (Gaussian filtered FSK) )
	(USART PC-MCU is 115200, configurable in 'printMsg.c')
	*/
	
	while(1)	listenRadio();
}
/* This software is provided by https://wildlab.org and
   Milan Karakas from Croatia. This is free program, but 
	 also "beerware". This means if you want this beta test
	 phase to grow into something really great, please consider 
	 some donation here: 
	 https://www.paypal.me/milankarakas?locale.x=en_US
	 It is still in beta test phase, and will be upgraded. 
	 So far it works at 433.120 MHz, and you need to change 
	 the frequency if you wish to something else - in library
	 'Si4432.c', there is math and you should to calculate 
	 and change values of the register for other frequencies. 
	 Out there exist also Si4432 - 868 MHz module, and this 
	 program works with this one too, but then you MUST change
	 the frequency, else output TX amplifier may burn. 
	 Later, will ad my own math to do that, but since it is still
	 in beta testing phase... stay tuned.
*/

#include "stm32f10x.h"

uint8_t reg=0, cmd=0;


void spiEnable(void)
{
	RCC->APB2ENR |= RCC_APB2ENR_IOPAEN|RCC_APB2ENR_AFIOEN; //already exist, but anyway...
	/* SPI pins */
	/* GPIO pin A4 is NSS ("Not" Slave Sellect), inverted... if low (0), then it is selected */
	GPIOA->CRL |= GPIO_CRL_CNF4_1|GPIO_CRL_MODE4_0|GPIO_CRL_MODE4_1;// 50 MHz - NSS (nSEL on Si4432)
	GPIOA->CRL &= ~GPIO_CRL_CNF4_0; //alternate function PP, this A4 pin must be high with external resistor 3kOhm to 4.7kOhm
	/* GPIO pin A5 is SPI clock SCK */
	GPIOA->CRL |= GPIO_CRL_CNF5_1|GPIO_CRL_MODE5_0|GPIO_CRL_MODE5_1;// 50 mhz - SCK
	GPIOA->CRL &= ~GPIO_CRL_CNF5_0; //alternate function PP
	/* GPIO pin A6 is MISO */
	GPIOA->CRL &= ~(GPIO_CRL_MODE6_0|GPIO_CRL_MODE6_1); // INPUT - MISO
	GPIOA->CRL |= GPIO_CRL_CNF6_0;
	/* GPIO pin A7 is MOSI */
	GPIOA->CRL |= GPIO_CRL_CNF7_1|GPIO_CRL_MODE7_0|GPIO_CRL_MODE7_1;// 50 MHz - MOSI
	GPIOA->CRL &= ~GPIO_CRL_CNF7_0; //alternate function PP
	
	/*  Configuring SPI */
	RCC->APB2ENR |= RCC_APB2ENR_SPI1EN;// SPI enable
	SPI1->CR1 |= SPI_CR1_BR_2;//|SPI_CR1_BR_1;//|SPI_CR1_BR_1|SPI_CR1_BR_0; // 72MHz/?
	SPI1->CR1 &= ~(SPI_CR1_CPOL|SPI_CR1_CPHA|SPI_CR1_DFF); // modes, 0 for polarity, and 0 for iddle clock=0, dff=0 (8 bit), lsbfirst=0 (MSB first), *
	SPI1->CR2 |= SPI_CR2_SSOE; //NSS enabled         
	SPI1->CR1 |= SPI_CR1_MSTR;// master configuration  
}

void spiWrite(int reg, int cmd)
{
  SPI1->CR1 |= SPI_CR1_SPE;
	SPI1->DR = (0x80|reg); //usually 0x80 does not belongs to SPI, but here it is "command mode", specific for Si4432
	while (!(SPI1->SR & SPI_SR_TXE)){}; 
	SPI1->DR = cmd; 
	while (!(SPI1->SR &SPI_SR_TXE)){}; 
	while(SPI1->SR & SPI_SR_BSY);
	while (!(SPI1->SR & SPI_SR_OVR)){}; //if single byte is sent,...
  SPI1->CR1 &= ~SPI_CR1_SPE;
}

int spiRead(int reg)
{
	SPI1->CR1 |= SPI_CR1_SPE;
	SPI1->DR =reg;
	while (!(SPI1->SR & SPI_SR_TXE)){};
	while(SPI1->SR & SPI_SR_BSY){}; //waiting little bit longer between two sendings
  SPI1->DR = 0x00; //dummy byte
	while (!(SPI1->SR & SPI_SR_RXNE)){};
	int rd=SPI1->DR; //dummy read? Whole thing does not working properly without
	while (!(SPI1->SR & SPI_SR_RXNE)){};
  int r=SPI1->DR;
	SPI1->CR1 &= ~SPI_CR1_SPE;
	return r;
}
#ifndef spi_h
#define spi_h

extern void spiEnable(void);
extern void spiWrite(int reg, int cmd);
extern int spiRead(int reg);

#endif
/* This software is provided by https://wildlab.org and
   Milan Karakas from Croatia. This is free program, but 
	 also "beerware". This means if you want this beta test
	 phase to grow into something really great, please consider 
	 some donation here: 
	 https://www.paypal.me/milankarakas?locale.x=en_US
	 It is still in beta test phase, and will be upgraded. 
	 So far it works at 433.120 MHz, and you need to change 
	 the frequency if you wish to something else - in library
	 'Si4432.c', there is math and you should to calculate 
	 and change values of the register for other frequencies. 
	 Out there exist also Si4432 - 868 MHz module, and this 
	 program works with this one too, but then you MUST change
	 the frequency, else output TX amplifier may burn. 
	 Later, will ad my own math to do that, but since it is still
	 in beta testing phase... stay tuned.
*/

#include "stm32f10x.h"
#include "delayUs.h"
#include "spi.h"
#include "si4432.h"
#include "printMsg.h"

int itStatus1=0,itStatus2=0;
int packetLength=0;
char payload[64];

void setModule(float freq, int power)
{
	// freq=433.120;
	int fc,fb,hbsel;
	
	if      (freq >240.00 && freq < 250.00) {fb=0;hbsel=0;}
	else if (freq >250.00 && freq < 260.00) {fb=1;hbsel=0;}
	else if (freq >260.00 && freq < 270.00) {fb=2;hbsel=0;}
	else if (freq >270.00 && freq < 280.00) {fb=3;hbsel=0;}
	else if (freq >280.00 && freq < 290.00) {fb=4;hbsel=0;}
	else if (freq >290.00 && freq < 300.00) {fb=5;hbsel=0;}
	else if (freq >300.00 && freq < 310.00) {fb=6;hbsel=0;}
	else if (freq >310.00 && freq < 320.00) {fb=7;hbsel=0;}
	else if (freq >320.00 && freq < 330.00) {fb=8;hbsel=0;}
	else if (freq >330.00 && freq < 340.00) {fb=9;hbsel=0;}
	else if (freq >340.00 && freq < 350.00) {fb=10;hbsel=0;}
	else if (freq >350.00 && freq < 360.00) {fb=11;hbsel=0;}
	else if (freq >360.00 && freq < 370.00) {fb=12;hbsel=0;}
	else if (freq >370.00 && freq < 380.00) {fb=13;hbsel=0;}
	else if (freq >380.00 && freq < 390.00) {fb=14;hbsel=0;}
	else if (freq >390.00 && freq < 400.00) {fb=15;hbsel=0;}
	else if (freq >400.00 && freq < 410.00) {fb=16;hbsel=0;}
	else if (freq >410.00 && freq < 420.00) {fb=17;hbsel=0;}
	else if (freq >420.00 && freq < 430.00) {fb=18;hbsel=0;}
	else if (freq >430.00 && freq < 440.00) {fb=19;hbsel=0;}
	else if (freq >440.00 && freq < 450.00) {fb=20;hbsel=0;}
	else if (freq >450.00 && freq < 460.00) {fb=21;hbsel=0;}
	else if (freq >460.00 && freq < 470.00) {fb=22;hbsel=0;}
	else if (freq >470.00 && freq < 480.00) {fb=23;hbsel=0;}
	else if (freq >480.00 && freq < 500.00) {fb=0;hbsel=1;}
	else if (freq >500.00 && freq < 520.00) {fb=1;hbsel=1;}
	else if (freq >520.00 && freq < 540.00) {fb=2;hbsel=1;}
	else if (freq >540.00 && freq < 560.00) {fb=3;hbsel=1;}
	else if (freq >560.00 && freq < 580.00) {fb=4;hbsel=1;}
	else if (freq >580.00 && freq < 600.00) {fb=5;hbsel=1;}
	else if (freq >600.00 && freq < 620.00) {fb=6;hbsel=1;}
	else if (freq >620.00 && freq < 640.00) {fb=7;hbsel=1;}
	else if (freq >640.00 && freq < 660.00) {fb=8;hbsel=1;}
	else if (freq >660.00 && freq < 680.00) {fb=9;hbsel=1;}
	else if (freq >680.00 && freq < 700.00) {fb=10;hbsel=1;}
	else if (freq >700.00 && freq < 720.00) {fb=11;hbsel=1;}
	else if (freq >720.00 && freq < 740.00) {fb=12;hbsel=1;}
	else if (freq >740.00 && freq < 760.00) {fb=13;hbsel=1;}
	else if (freq >760.00 && freq < 780.00) {fb=14;hbsel=1;}
	else if (freq >780.00 && freq < 800.00) {fb=15;hbsel=1;}
	else if (freq >800.00 && freq < 820.00) {fb=16;hbsel=1;}
	else if (freq >820.00 && freq < 840.00) {fb=17;hbsel=1;}
	else if (freq >840.00 && freq < 860.00) {fb=18;hbsel=1;}
	else if (freq >860.00 && freq < 880.00) {fb=19;hbsel=1;}
	else if (freq >880.00 && freq < 900.00) {fb=20;hbsel=1;}
	else if (freq >900.00 && freq < 920.00) {fb=21;hbsel=1;}
	else if (freq >920.00 && freq < 940.00) {fb=22;hbsel=1;}
	else if (freq >940.00 && freq < 960.00) {fb=23;hbsel=1;}
	
	fc=((freq*1e6)/(10e6*(hbsel+1))-fb-24)*64000;
	
		/* should be interrupt for usart */
	USART1->CR1 |= USART_CR1_RXNEIE;  //setting only IRQ which 'listen' input of the MCU (message from PC) 
	NVIC_EnableIRQ(USART1_IRQn); //enabling IRQ
	
	RCC->APB2ENR |= RCC_APB2ENR_IOPAEN|RCC_APB2ENR_AFIOEN; //already exist, but anyway...
	/* Setting output GPIO pin A2 for SDN pin on Si4432 */
	GPIOA->CRL |= GPIO_CRL_MODE2_0|GPIO_CRL_MODE2_1; //pin A2 - OUTPUT - 50 MHz - SDN at Si4432
	GPIOA->CRL &= ~(GPIO_CRL_CNF2_1|GPIO_CRL_CNF2_0); //not sure.... leave 00 - general purpose PP
	/* Setting input GPIO pin A3 for nIRQ pin on Si4432 */
	GPIOA->CRL &= ~(GPIO_CRL_CNF3_0|GPIO_CRL_MODE3_0|GPIO_CRL_MODE3_1); //pin A3 - INPUT - nIRQ at Si4432
	GPIOA->CRL |= GPIO_CRL_CNF3_1; //INPUT, floating (!) Si4432 has high level if IRQs are set
		
	/* Configuring radio */
	GPIOA->BSRR = GPIO_BSRR_BS2; //Hardware reset - SDN pin goes up for 5 mS, then remains down at zero
	delay(500000); //watch LEDs on GPIO 2, if there is inproper reset, then GPIO 2 will give default 1 MHz at this pin
	GPIOA->BSRR = GPIO_BSRR_BR2;// pull down SDN pin on Si4432 to turn on radio
	delay(17000);//wait 17 mS or more, Si4432 internal startup
	
	/* Software reset (SW reset) */
	spiWrite(0x07, 0x80); //software reset on Si4432
	delay(30000);//at least 2 mS, leave it at 3 mS, else it may skip next while loop and not working properly

	while((GPIOA->ODR & GPIO_IDR_IDR3)); //Waiting nIRQ to become low
	//printMsg("IRQ received \n"); //debug only
	spiWrite(0x0a, 0b00001111); //GPIO2 gives 32.768 kHz if line below is not included:
	spiWrite(0x0d, 0b00000001); //but, lets turn off GPIO2, no frequency out if reset is properly done
	
	/* Set the physical parameters, example freq.=433.120 MHz*/
	//spiWrite(0x75,0x40|0x13); //frequency band select (0x40= 64, 0x13= 19 total= 0x53 = 83 decimal) (band select+fb value)-old for 433.120
	spiWrite(0x75, ((1<<6)|(hbsel<<5 )|(fb & 0x1F))); //
	// (0x75)        0       1     0    10011  
	// register: |reserved|sbsel|hbsel|fb[4:0]|
	spiWrite(0x76,(fc>>8)); //Nominal carrier frequency 1 (0x4D = 77 decimal), fc[15:8] (fine tuning?)
	//spiWrite(0x76,0x4e); //old fixed value for 433.120 MHz
	spiWrite(0x77,(fc & 0xFF)); //Nominal carrier frequency 2 (0xFF = 255 decimal),  fc[7:0]  (fine tuning?)
	//spiWrite(0x77, 0x00);//old fixed value for 433.120 MHz
	/* F(carrier)= 10e6*(hbsel+1)*(N+F) */
	/* F(TX)= 10e6*(hbsel+1)*(fb[4:0]+24+(fc[15:0]/64000) */
	/* F=(TX) 10e6*(1+1)*(19+24+(19968/64000)= 433.120 MHz */
	/* fc[15:0]=((wanted frequency in MHz/10e6*(hbsel+1))-fb[4:0]-24)*64000 */
	/* Please take look at page 26 with "Frequency Band Selection", Si4432 datasheet for fb[4:0] and N values. */
	
	
	/* Set desired TX data rate (9600 bps) */
	spiWrite(0x6E, 0x4E); //TX data rate 1, txdr[15:8]
	spiWrite(0x6F, 0xA5); //TX data rate 2  txdr[7:0] (together, txdr[15:0]= 0x4EA5, or 20133 decimal
	spiWrite(0x70, 0x2C); //Modulation Mode Control 1 (0x2C= 0b00101100)
	//  (0x70)        0        0         1         0        1        1       0       0
	// register: |reserved|reserved|txdtrtscale|enphpwdn|manppol|enmanihv|enmanch|enwhite|
	/* DR_TX(bps) = (txdr[15:0]*1 MHz)/(2^(16+5*txdrtscale)) */
	/* DR_TX(bps) = 20133*1e6/2^(16+5*1)= 9600.162506...  */
	/* txdr[15:0]= (DR_TX*(2^(16+5*txdtrtscale))/1 MHz */
	/* txdr[15:0]= 9600*(2^(16+5*1)/1e6= 20132.6595, rounded to 20133, hexadecimal= 0x4EA5, 0x4E goes to txdr[15:8], 0xA5 goes to txdr[7:0] */
	
	/* Set TX deviation register (+/- 5 kHz), or deltaF= 10 Khz, registers 0x71 and 0x72, but if fd[8] is zero, we can skip that register */
	spiWrite(0x72,0x10); //for 9600 bps, 625 kHz*16= 10 kHz, part of 9 bites (!), fd[7:0], MSB bit is in register 0x71 (fd[8])
	/* deltaF= fd[8=0]*625 Hz */
	/* deltaF= 16*625= 10000 Hz */
	/* fd[8:0]= deltaF/625 Hz */
	/* fd[8:0]= 10e3/625= 16 decimal, or 0x10 hexadecimal goes to txdr[8:0] */
	
	/* Set modem parameters according to the excel calculator for 9600 bps, deviation 45 kHz, channel filter BW: 102.2 kHz */
	spiWrite(0x1C, 0x12); //IF filter bandwidth (probably the same math as with TX deviation, or maybe slightly higher value?)
	spiWrite(0x20, 0xD0); //Clock recovery oversampling (?) (no any explanation in the datasheet for all things below)
	spiWrite(0x21, 0x00); //Clock recovery offset 2 (?)
	spiWrite(0x22, 0x9D); //Clock recovery offset 1 (?)
	spiWrite(0x23, 0x49); //Clock recovery offset 0 (?)
	spiWrite(0x24, 0x00); //Clock recovery timing loop gain (?)
	spiWrite(0x25, 0x24); //Clock recovery timing loop gain (?)
	spiWrite(0x1D, 0x40); //AFC loop gearshift override (?)
	spiWrite(0x1E, 0x0A); //AFC timing control register (?)
	spiWrite(0x2A, 0x20); //AFC limiter register (?)
	
	/* Set packet structure and modulation type, set preamble length to 5 bytes */
	spiWrite(0x34, 0x20); //Preamble length register, 0xA = 10 decimal, probably 1010101010 (10 bits)
	spiWrite(0x35, 0x14); //Preable detection control (threshold 42 bits for (G)FSK with AFC enabled)
	spiWrite(0x33, 0x02); //disalbe header bytes, Header control 2 
	spiWrite(0x36, 0x2D); //2D is sync word 3 (0b00101101)
	spiWrite(0x37, 0xD4); //D4 is sync word 2 (0b11010100), sync word 0 not used, so register 0x38 is omitted
	
	/* Enable TX & RX packet handler and CRC-16 (IBM) check */
	spiWrite(0x30, 0x8D); //Data access control register
	// (0x30)        1        0       0        0       1      1      01
	// register: |enpacrx|lsbfirst|crcdonly|skip2ph|enpactx|encrc|crc[1:0]|
	spiWrite(0x32, 0x00); //Header control 1 (disabling receive header filters)
	spiWrite(0x71, 0x63); //Modulation mode control 2
	// (0x71)          01         10       0     0       11
	// register: |trclk[1:0]|dtmod[1:0]|eninv|fd[8]|modtyp[1:0]|, fd[8] is MSB for fd[8:0] that can be found in reg. 0x72
	spiWrite(0x0B, 0b00010010 ); //GPIO 1 (set TX state) was 0x12
	spiWrite(0x0C, 0b00010101); //GPIO 2 (set RX state) was 0x15
	
	/* Non default Si443x registers */
	spiWrite(0x09, 0xA9); //Crystal oscillator load (Leave it as-is. Or, you can fine tune 30 MHz oscillator if you have precise freq.meter)0xAA
	spiWrite(0x69, 0x60); //Override 1 register (?)
	// (0x69)         0     1    1      0      0000
	// register: |reserved|sgi|agcen|lnagain|pga[3:0]|
	
	/* Enable receiver chain */
	spiWrite(0x07, 0x05); //Operating function control 1 reg.
	// (0x07)       0     0     0     0      0    1    0    1
	// register: |swres|enlbd|enwt|x32ksel|txon|rxon|pllon|xton|, enabling only RX and Xtall (30 MHz crystal)
	spiWrite(0x05, 0x03); //Interrupt enable 1 ('ipkval', and 'encrcerror') valid packet received
	// (0x05)        0         0          0          0        0      0          1        1
	// register: |enfferr|entxffafull|entxffaem|enrxffafull|enext|enpksent|enpkvalid|encrcerror|
	spiWrite(0x06, 0x00); //Interrupt enable 2 (actually not enabling anything, just in case you need RSSI, then use 'enrssi')
	// (0x06)        0        0          0        0     0     0       0       0
	// register: |enswdet|enpreaval|enpreinval|enrssi|enwut|enlbd|enchiprdy|enpor|
	
	/* Read interrupt status registers */
	itStatus1=spiRead(0x03);; //read Interrupt status 1
	itStatus2=spiRead(0x04);; //read Interrupt status 2
  //printMsg("itStatus1= %d, itStatus2= %d\n",itStatus1,itStatus2);
	
	/* Power settinigs */
	spiWrite(0x6D, (power&0x07)); //Power, from 0 to 7, max power is 100 mW 
	// (0x6D)         0        0        0       0        0      000
	// register: |reserved|reserved|reserved|reserved|lna_sw|txpow[2:0]|
}

void USART1_IRQHandler(void)
{
	USART1->CR1 &= ~USART_CR1_RXNEIE; //as soon as it enters IRQ, forbid re-triggering IRQ
	len=readMsg()+1;
  int fraction;
	/* Sending message just received over USART - lets disable receiver first and clear TX buffer */
	spiWrite(0x07, 0x01); //disabling receiver
	fraction = ((len)%64); //we should to know how how many packets of 64 + the rest of bytes...
  if ((len)<65)
  {
		 spiWrite(0x08, 0x01); //clearing TX FIFO buffer
	   spiWrite(0x08, 0x00); //removing clearing bit
	   for (int s=0;s<(len);s++)
    {
	    spiWrite(0x7F, buff[s]);
    }
		spiWrite(0x3E, (len));
    spiWrite(0x05, 0x04); //interrupt 1 enable ('enpktsent')
    spiWrite(0x06, 0x00); //interrupt 2 enable (actually nothing enabled)
    spiWrite(0x07, 0x09); //Sending packet of 64 bytes
    while((GPIOA->IDR & GPIO_IDR_IDR3)){}; // waiting for confirmation that packet is sent, nIRQ goes low if done
    //printMsg("small packet sent %d\n", len);
	}
 	else
	{			
   	for (int p=0;p<(len-fraction);p+=64)
		{
			spiWrite(0x08, 0x01); //clearing TX FIFO buffer
			spiWrite(0x08, 0x00); //removing clearing bit
			for (int b=0;b<64;b++)
				{
					spiWrite(0x7F, buff[b+p]);
				}
				spiWrite(0x3E, 64); // If it gets here, packet length will be always 64 bytes long, so no need to put calculation or anything else
				spiWrite(0x05, 0x04); //interrupt 1 enable ('enpktsent')
				spiWrite(0x06, 0x00); //interrupt 2 enable (actually nothing enabled)
				spiWrite(0x07, 0x09); //Sending packet of 64 bytes
				while((GPIOA->IDR & GPIO_IDR_IDR3)){}; // waiting for confirmation that packet is sent, nIRQ goes low if done
				itStatus1=spiRead(0x03);; //read Interrupt status 1
	      itStatus2=spiRead(0x04);; //read Interrupt status 2
				//printMsg("Part of the packet sent= %d num= %d\n",(temp+1), p);
		}
		spiWrite(0x08, 0x01); //clearing TX FIFO buffer
		spiWrite(0x08, 0x00); //removing clearing bit
		for (int f=0;f<fraction;f++)
			{
			spiWrite(0x7F, buff[((len)-fraction)+f]);
			}
			spiWrite(0x3E, fraction);
			spiWrite(0x05, 0x04); //interrupt 1 enable ('enpktsent')
			spiWrite(0x06, 0x00); //interrupt 2 enable (actually nothing enabled)
			spiWrite(0x07, 0x09); //Sending packet of 64 bytes
			while((GPIOA->IDR & GPIO_IDR_IDR3)){}; // waiting for confirmation that packet is sent, nIRQ goes low if done
			//printMsg("remaining packet sent %d\n",fraction);
	}		
	USART1->CR1 |= USART_CR1_RXNEIE; //after everything done here, re-enable IRQ
}
			
void listenRadio(void)
	{
		/* Enable receiver chain and listening RX*/
		spiWrite(0x08, 0x02); //operating function control 2 reg. clearing TX and RX FIFO buffer, register bit 'ffclrrx'
		spiWrite(0x08, 0x00); //operating function control 2 reg. not sure why it should go back to zero, but it must be tehere
		
		/* Set interrupts for valid packet ('ipkval'), or CRC error ('encrcerror') */
		spiWrite(0x07, 0x05); // RX on

	  /* Wait for interrupt event */
    while((GPIOA->IDR & GPIO_IDR_IDR3)); //if nothing received, then it will "stuck" here forever
		spiWrite(0x05, 0x03); //interrupt enable 1 'ipkval' and encrcerror'
		spiWrite(0x06, 0x00); //interrupt enable 2, but this time nothing is enabled
		// RSSI value is in register 0x26, and threshold for "clear RSSI" in 0x27 (RSSI is not zero when no signal, there is some noise)
		spiWrite(0x07, 0x01); //disabling receiver during received packed testing, but leave xtall on
		
		/* Checking for errors first */
		itStatus1=spiRead(0x03);; //read Interrupt status 1
	  itStatus2=spiRead(0x04);; //read Interrupt status 2
	  //printMsg("* itStatus1= 0x%X, itStatus2= 0x%X \n",itStatus1,itStatus2); //debug only
			
		/* if CRC error interrupt occured ? : disabled because from time to time some RF noise trigger it without 'real' transmission at the other end.
			if ((itStatus1 & 0x01) ==0x01)  // 0x01 = 'icrcerror' in register 0x03 on Si4432
			{
				printMsg("CRC error \n");
			}
			*/
			/* Valid packet received interrupt occured ? */
			if ((itStatus1 & 0x02) == 0x02)  // 0x02 = 'ipkvalid' in register 0x03 on Si4432
			{
				packetLength=spiRead(0x4B); //read length of the recieved packet
				//printMsg("received packet length= %d \n", packetLength); //debug only
				for (int i=0;i<packetLength;i++)
				{
					payload[i]=spiRead(0x7F); //read FIFO
					printMsg("%c",(char)payload[i]); //print character by character
				}
        //printMsg("\n");	//Line Feed (LF) no needed, since we sending it over the radio
			}
			spiWrite(0x08, 0x02); // clearing TX and RX FIFO buffer, register bit 'ffclrrx'
		  spiWrite(0x08, 0x00); // not sure why it should go back to zero, but it must be tehere
	}
#ifndef si4432_h
#define si4432_h

extern int itStatus1,itStatus2;
extern int packetLength;
extern char payload[];

extern void setModule(float freq,int power);
extern void listenRadio(void);

#endif
/* This software is provided by https://wildlab.org and
   Milan Karakas from Croatia. This is free program, but 
	 also "beerware". This means if you want this beta test
	 phase to grow into something really great, please consider 
	 some donation here: 
	 https://www.paypal.me/milankarakas?locale.x=en_US
	 It is still in beta test phase, and will be upgraded. 
	 So far it works at 433.120 MHz, and you need to change 
	 the frequency if you wish to something else - in library
	 'Si4432.c', there is math and you should to calculate 
	 and change values of the register for other frequencies. 
	 Out there exist also Si4432 - 868 MHz module, and this 
	 program works with this one too, but then you MUST change
	 the frequency, else output TX amplifier may burn. 
	 Later, will ad my own math to do that, but since it is still
	 in beta testing phase... stay tuned.
*/

#include "stm32f10x.h"
#include "stdint.h"
#include <stdio.h>
#include "stdarg.h"
#include "string.h"
#include "printMsg.h"

#define buffer 20000
char buff[buffer]; //10000 characters! If you need less, then change this value AND (!) value value below as well

void usart_1_enable(void)
{
  //enabling pin A9 for alternating funct. for uart/usart
  RCC->APB2ENR |= RCC_APB2ENR_IOPAEN | RCC_APB2ENR_AFIOEN | RCC_APB2ENR_USART1EN; //clock to GPIO A enabled, port A(2), alt.funct.en(0), usart1 clock enabled(14)
	GPIOA->CRH |= GPIO_CRH_CNF9_1 | GPIO_CRH_MODE9_0 | GPIO_CRH_MODE9_1; //port A9 TX
	GPIOA->CRH &= ~GPIO_CRH_CNF9_0; //port A9
	GPIOA->CRH &= ~(GPIO_CRH_MODE10_0|GPIO_CRH_MODE10_1); //port A10 is RX
	GPIOA->CRH |= GPIO_CRH_CNF10_0; //port A10 is RX
	
	//GPIOA->CRH = 0x444444B4; // A9 is alternate output, 50 MHz, push-pull - not this time short version (!)
	//clkPer/(baudRx_16bit)=72MHZ/9600 = 7500 = 0x1D4C
	/* Remove comment line for speed that you want to use*/
	//USART1->BRR = (0xEA60); //   1200 Baud
	//USART1->BRR = (0x7530); //   2400 Baud
	//USART1->BRR = (0x3A98); //   4800 Baud
	//USART1->BRR = (0x1D4C); //   9600 Baud
	//USART1->BRR = (0x1388); //  14400 Baud
	//USART1->BRR = (0xEA6) ; //  19200 Baud
	//USART1->BRR = (0x9c4) ; //  28800 Baud
	//USART1->BRR = (0x753) ; //  38400 Baud
	//USART1->BRR = (0x505) ; //  56000 Baud
	//USART1->BRR = (0x4E2) ; //  57600 Baud
	USART1->BRR = (0x271) ; // 115200 Baud
	//USART1->BRR = (0x232) ; // 128000 Baud
	//USART1->BRR = (0x119) ; // 256000 Baud
	//USART1->BRR = (0x8C)  ; // 512000 Baud
	//USART1->BRR = (0x46)  ; // 1024000 Baud
	//USART1->BRR = (0x23)  ; // 2048000 Baud
  //USART1->BRR = (0x18)  ; // 3000000 Baud (3 MHz, max speed that HTerm can get, non-standard speed)
	
	
	USART1->CR1 |= USART_CR1_TE; //transmitter enable
	USART1->CR1 |= USART_CR1_RE; //receiver enable
	USART1->CR1 |= USART_CR1_UE; //usart enable
}

void printMsg(char *msg, ...)
{
	//char buff[120]; //was 80
	va_list args;
	va_start(args,msg); 
	vsprintf(buff,msg,args);

	for(int i=0;i<strlen(buff);i++)
	{
	  USART1->DR = buff[i];
	  while(!(USART1->SR & USART_SR_TXE)); //wait for TXE, 1 = data transferred
  }
}

int readMsg(void)
{ 
  
 for( len =0;len<buffer;len++)  //20000 characters! If you need less, then change this value AND (!) buff[] value above as well.
 {
    while(!(USART1->SR & USART_SR_RXNE));
    buff[len]= USART1->DR;
    if (buff[len]==10 || buff[len]==13) break; //if enter is pressed, providing that it is 10 or 0xA (line feed), or 13 (0xD) (carriage return) 
 }
 return len; //just returning number of entered characters, not including line feed nor carriage return (!)
}
#ifndef printMsg_h
#define printMsg_h

extern int len;
extern char buff[];
//char buff[];

void usart_1_enable(void);
void printMsg(char *msg, ...);
int readMsg(void);
void USART1_IRQHandler(void);

#endif

 

STM32 write and read EEPROM over I2C bus

EEPROM write and read

EEPROM sounds intimidating for the beginners, probably because there are few rules to comply. First, all EEPROMs share the same address on I2C bus, at least first page, and that is 0x50. I will give example for Atmel 24C08 chip, which has 8 kbit (!) memory. This number is NOT killo-bytes, but 1024 x 8 bits. So, practically ‘only’ 1 KB of memory space. Second rule is that writing must be done in sequence(s) of 8 or 16 bytes, depending of memory type. 1k and 2k EEPROMs can write only 8 bytes at a time, but 4k/8k/16k can write 16 bytes at a time. Between each write cycles and write then read cycle should be about 2 mS delay. This delay is some intrinsic property of the memory, and we can’t do anything about that. Only follow the rule. Read is possible whole ‘page’ of 256 bytes at once. Also, there is no restriction between two readings. Only after writing even singly byte, must be some delay, experimentally found 1.68 ms, so better use 2 mS (2000 uS) for sure.

Splitting data into groups of 16 bytes

That is how it should works. I made relatively simple code for STM32f10x family of the MCUs. In this code, there is two examples, one writing just 16 bytes, another one writing more than that in few steps with delay of 2 mS between each ‘packets’ of 16 bytes. Second example uses second of four pages. First example is on first page. Each page has actually its own I2C address ranging from 0x50 to 0x57 for 16k EEPROMs. I have only one chip that has 8k, so it covers four pages; page 0 = 0x50, page 1 = 0x51, page 2 = 0x52, and page 3 = 0x53. I found this chip below board with STM32f103VET6, that was surprise for me. Did not found any data about that board, nor it is mentioned in STM32 literature. And since this STM32 board has no ‘name’ as is for example Arduino uno, no data about this one except few words on eBay (plus price tag 😀 ).

In the example code I did not make algorithm for writing whole chip, because in practice this type of memory is just for few variables, maybe some calibration data or whatever user need to change after programming MCU, or during. For example, some servo has offset where middle position is not exactly in the middle. So, we can make code that scan buttons which moves servo, and when servo is where we want to be, another button press save calibration data into EEPROM. Since I did not use this chip in the past, I can’t give any example for now, but for sure it will be here in the future.

Code(s) not complete. Why?!

Please look carefully the examples. First example is not implemented correctly. I have doubt – do I need finish everything to show you, or you can learn something and recognize how to solve ‘the puzzle’? Second example, just un-comment (remove ‘//’) two separate functions twiSend(), twiReceive() and one printMsg() . That is last printMsg() which read all 255 bytes from second page at 0x51.  Also, you may notice that there are three strange variables included: ‘num’, ‘mantissa’ and ‘fraction’. Variable ‘num’ uses function strlen(test2) to get number of characters needed for two ‘for(;;)’ loops. In for example we have 92 characters, then 92/16 =5.75. Mantissa is number 5 (currently no needed in those examples), 0.75 is fraction, but (!) expressed in remaining bytes, that is 0.75*16=12.

Very interesting first loop:

for (int p=0;p<(num-fraction);p+=16)

This one uses number of characters (for example 92), subtract fraction (say 12), then it goes NOT from 0 to 92, but from 0 to 80 in steps of 16. Then some conversion of characters into uint8_t form. Not ideal, but… Then function twiSend(0x51,p,16) sends first 16 bytes, then another 16 until reaches 80. Then it exits for(;;) loop, and send the remaining 12 bytes twiSend(0x51,(num-fraction),fraction). At this time, ‘num-fraction’ is 92-12=80, which means that it begins to write at position 80 in EEPROM memory, for next ‘fraction’, which is 12 bytes.  After you copy/paste those codes, please align everything, because operation copy/paste onto this page can ruing alignment.

Here are the codes:

/*placeholder for page URL
This is just an example. You can modify this code (it is free)
as you wish and adapt to your needs. 
*/

#include "stm32f10x.h"
#include "printMsg.h"
#include "wire.h"
#include "delayUs.h"
#include "string.h"

//uint8_t address=0; 
uint8_t buffer[1024];

int main()
{
	usart_1_enable(); //enabling printMsg();
	twiEnable();//enabling two wire interface twiEnable(); that is our I2C1
	
/*Next function wroks only if you #include "printMsg.h" in library (also #include wire.h)	wire.c 
	(is included when you include .h lib.), there is already printMsg() function that will send to 
	USART1 message about addresses that is found on the I2C bus (here, only I2C1 bus). Note that 
	some STM32 boards has already EEPROM (8 Kbit) on the bottom of the PCB. Example is STM32F103VET6 */
	
 	//twiScan();//before anything else, lets check which devices are on the bus, 

	 /* EEPROM example writting and reading 16 bytes (4K/8K/16K only) at first page (0x50) with some message */

	char test[]={"This is for test"}; //test write to EEPROM, 1K/2K only 8 bytes, 4K/8K/16K maximum 16 bytes at once
	//            1234567890123456    (helper to see when it 'fit' into 16 bytes for 4K/8K/16K EEPROMs, can be less than 16 bytes, but not more)

	for (int i=0;i<strlen(test);i++)
	{
		buffer[i]=test[i]; //filling (uint8_t)buffer[] with (char)test
	}
  //twiSend(0x50,0,strlen(test)); //sending first 'packet' to the EEPROM at address 0x50 from position 0
  delay(2000); //minimum time to wait is 1.658 mS, so use 1 mS, or better 2000 uS, else it will stuck
  //twiReceive(0x50,0,40); //receiver from first page at 0x50
  for (int i=0;i<strlen(test);i++)
	{
		//printMsg("%c",buffer[i]);//here %c means that we will print characters. If you want, you may try %c and you will get ASCII values
	}
	
	/* EEPROM example writing and reading more than 16 bytes in few sequences*/
	
	char test2[]={"This is example of writing EEPROM memory more than 16 bytes - in sequences of 16 bytes + 12 ."};
//             12345678901234567890123456789012345678901234567890112345678901234567890123456789012345678901234567890
	//             |       10     |  20        30 |      40       |50         60   |    70        8|0       90     |   100... (decades)
	//             0             16              32              48               64              80              96...  (hexadecimals)
 
	//int mantissa; 
	int fraction; 
	int num;
	
	num=strlen(test2);
	//mantissa=num/16;
	fraction=num%16;
	
	for (int p=0;p<(num-fraction);p+=16)
	{
	  for (int b=0;b<16;b++)
		{
			buffer[b]=test2[b+p];//lets put packets of 16 bytes into buffer
		}
		twiSend(0x51,p,16);	//second page (0x51), but you can do it at any other pages from 0x50 to 0x57 (if your EEPROM has that much memory)
    delay(2000); //wait 2 mS between two EEPROM access
	}
	for (int i=0;i<fraction;i++)
	{
		buffer[i]=test2[(num-fraction)+i];
	}
	delay(2000); //wait 2 mS between two EEPROM access
  twiSend(0x51,(num-fraction),fraction); 

	delay(2000);
	//twiReceive(0x50,0,120); //receiving bytes stored in EEPROM in the first example written way above, first page
	//for (int i=0;i<255;i++) printMsg("%c",buffer[i]); printMsg("\n");
	
	delay(2000);
	twiReceive(0x51,0,255); //receiving bytes stored in EEPROM in the second example above, second page
	for (int i=0;i<255;i++)	printMsg("%c",buffer[i]); printMsg("\n");
}
/* Two Wire Interface, I2C (or IIC), here will be called 'twi', and we have
   only twiEnable(), twiSend() and twiReceive(). The twiSend() function is 
	 fairly simple, we just send address of the device shifted to the left by
	 1 bit, or-red | zero (0) at free space that tell I2C bus it is for write operation.
	 The receive twiReceive() function works by sending address also shifted left
	 one bit with logic or | zero (0) at empty bit (LSB), but then we must send command 
	 to the device depending what device has. After command, we stop (although
	 we can remove STOP condition and continue to "repeated start", then we
	 must change bit after address of the device, now it is one (1) that tells
	 I2C bus we want to read. If we try only read from some address, device
	 don't know what to send. So we must first issue command, then read. For
	 specific command set read datasheet of particular device - it is different
	 for all different devices. More on my website: http://wp.me/p7jxwp-nD */

#include "stm32f10x.h"
#include "delayUs.h"
#include "wire.h"
#include "printMsg.h"

void twiEnable(void) 
{
  //just set all registries, but NOT START condition - execute once in main.c
	RCC->APB2ENR |= RCC_APB2ENR_IOPBEN | RCC_APB2ENR_AFIOEN; //B port enabled, alternate function 
	RCC->APB1ENR |= RCC_APB1ENR_I2C1EN; //I2C 1 enabled 
	GPIOB->CRL = 0xFF000000;// setting just pins B7 (SDA) and B6 (SCL), while leaving the rest intact 50 MHz!
	I2C1->CR2 |= 50; // GPIO clock freq=50 MHz MUST !!! be equal APB frequency (GPIO, 2, 10 or 50 MHz)
	I2C1->CCR |= I2C_CCR_FS; //fast mode
	I2C1->CCR |= 30; //not sure for 400 000 - (10= 1.2 MHz, 15=800 kHz, 30=400 kHz)
	I2C1->TRISE |= 51; // maximum rise time is 1000 nS
	I2C1->CR1 |= I2C_CR1_PE; 
}

void twiScan(void)
{		int a=0; 
	 	for (uint8_t i=0;i<128;i++)
   {
			I2C1->CR1 |= I2C_CR1_START;
			while(!(I2C1->SR1 & I2C_SR1_SB));
			I2C1->DR=(i<<1|0); 
			while(!(I2C1->SR1)|!(I2C1->SR2)){}; 
			I2C1->CR1 |= I2C_CR1_STOP; 
			delay(100);//minimum wait time is 40 uS, but for sure, leave it 100 uS
			a=(I2C1->SR1&I2C_SR1_ADDR);
			if (a==2)
		 {
				printMsg("Found I2C device at adress 0x%X (hexadecimal), or %d (decimal)\n",i,i);
		 }
	 }
}
	
/* Command or commands, or sending bytes, just the same name of the variable 'command' */
void twiSend(uint8_t address, uint8_t command, uint8_t length)
{
	I2C1->CR1 |= I2C_CR1_START; //START condition 
	while(!(I2C1->SR1 & I2C_SR1_SB));
	I2C1->DR=(address<<1|0); //sending address of the device, 0 = sending
  while(!(I2C1->SR1 & I2C_SR1_ADDR)|!(I2C1->SR2));		
	I2C1->DR=command; //filling data register with byte, if single - command, multiple - command(s) and data
	for (uint8_t i=0;i<length;i++)
	{ 
		I2C1->DR=buffer[i]; //filling buffer with command or data
		delay(60);
	}
	I2C1->CR1 |= I2C_CR1_STOP;
}

void twiReceive(uint8_t address, uint8_t command, uint8_t length) 
{
	I2C1->CR1 |= I2C_CR1_ACK;
  I2C1->CR1 |= I2C_CR1_START; //start pulse 
	while(!(I2C1->SR1 & I2C_SR1_SB));
	I2C1->DR=(address<<1|0); //sending address of the device, 0 = sending
	while(!(I2C1->SR1 & I2C_SR1_ADDR)|!(I2C1->SR2 & I2C_SR2_BUSY));
	I2C1->DR=command; //sending command to the device in order to request data
	I2C1->CR1 |= I2C_CR1_START; //REPEATED START condition to change from sending address + command to receive data
	while(!(I2C1->SR1 & I2C_SR1_SB));
	I2C1->DR=(address<<1|1); //sending address of the device, 1 = reading 
	while(!(I2C1->SR1 & I2C_SR1_ADDR)|!(I2C1->SR2));
	
if (length==1)  //receiving single byte, N=1
	{
		while(!(I2C1->SR1)|!(I2C1->SR2));
		I2C1->CR1 &= ~I2C_CR1_ACK; //this will send later NAK (not acknowledged) to signal it is last byte
		I2C1->CR1 |= I2C_CR1_STOP; //issuing STOP condition before (!) reading byte
		buffer[0]=I2C1->DR; //single byte is read AFTER NAK (!) and STOP condition
	} 
	if (length==2) //receiving two bytes, N=2
	{
		while(!(I2C1->SR1)|!(I2C1->SR2));
		I2C1->CR1 &= ~I2C_CR1_ACK; //this will send later NAK (not acknowledged) before last byte
    I2C1->CR1 |= I2C_CR1_STOP;
		buffer[0]=I2C1->DR; //reading N-1 byte, next to last byte is in DR, last one still in shift register
		while(!(I2C1->SR1 & I2C_SR1_RXNE)|!(I2C1->SR2));
		buffer[1]=I2C1->DR; //read last N byte now available 
	} 
  if (length>2) //receiving more than two bytes, N>2
	{
		
	  for (uint8_t i=0;i<length;i++)
	  { 
			                     
		  if (i<(length-3))      // if it is not N-2, then read all bytes
			{
				while(!(I2C1->SR1 & I2C_SR1_RXNE)|!(I2C1->SR2));
				buffer[i]=I2C1->DR;  
			}
		  else if (i==length-3) // if it is N-2 then read 
			{
				while(!(I2C1->SR1)|!(I2C1->SR2));
				buffer[i]=I2C1->DR; 
				while(!(I2C1->SR1 & I2C_SR1_RXNE)|!(I2C1->SR2));
				I2C1->CR1 &= ~I2C_CR1_ACK; //this will send later NAK (not acknowledged) before last byte
				I2C1->CR1 |= I2C_CR1_STOP;
			}
	    else if (i==length-2) // if it is N-1 then read
			{
				while(!(I2C1->SR1 & I2C_SR1_RXNE)|!(I2C1->SR2));
				buffer[i]=I2C1->DR; 
			}
			else if (i==length-1) // else it is N byte 
			{
				while(!(I2C1->SR1 & I2C_SR1_RXNE)|!(I2C1->SR2)){};
		    buffer[i]=I2C1->DR;  
			}
    } 
 }
}
#ifndef wire_h
#define wire_h

#include <stdint.h>

extern uint8_t  address, command, length; 
extern uint8_t  buffer[];
extern uint8_t  status1;
extern uint8_t  status2;

void twiEnable(void);
void twiScan(void);
void twiSend(uint8_t address, uint8_t command, uint8_t length);
void twiReceive(uint8_t address, uint8_t command, uint8_t length);


#endif
#include "stm32f10x.h"
#include "stdint.h"
#include <stdio.h>
#include "stdarg.h"
#include "string.h"
#include "printMsg.h"

char buff[256];

void usart_1_enable(void)
{
  //enabling pin A9 for alternating funct. for uart/usart
  RCC->APB2ENR |= RCC_APB2ENR_IOPAEN | RCC_APB2ENR_AFIOEN | RCC_APB2ENR_USART1EN; //clock to GPIO A enabled, port A(2), alt.funct.en(0), usart1 clock enabled(14)
	GPIOA->CRH |= GPIO_CRH_CNF9_1 | GPIO_CRH_MODE9_0 | GPIO_CRH_MODE9_1; //port A9
	GPIOA->CRH &= ~GPIO_CRH_CNF9_0; //port A9
	GPIOA->CRH &= ~(GPIO_CRH_MODE10_0|GPIO_CRH_MODE10_1); //port A10 is RX
	GPIOA->CRH |= GPIO_CRH_CNF10_0; //port A10 is RX
	
	//GPIOA->CRH = 0x444444B4; // A9 is alternate output, 50 MHz, push-pull - not this time short version (!)
	//clkPer/(baudRx_16bit)=72MHZ/9600 = 7500 = 0x1D4C
	/* Remove comment line for speed that you want to use*/
	//USART1->BRR = (0xEA60); //   1200 Baud
	//USART1->BRR = (0x7530); //   2400 Baud
	//USART1->BRR = (0x3A98); //   4800 Baud
	//USART1->BRR = (0x1D4C); //   9600 Baud
	//USART1->BRR = (0x1388); //  14400 Baud
	//USART1->BRR = (0xEA6) ; //  19200 Baud
	//USART1->BRR = (0x9c4) ; //  28800 Baud
	//USART1->BRR = (0x753) ; //  38400 Baud
	//USART1->BRR = (0x505) ; //  56000 Baud
	//USART1->BRR = (0x4E2) ; //  57600 Baud
	USART1->BRR = (0x271) ; // 115200 Baud
	//USART1->BRR = (0x232) ; // 128000 Baud
	//USART1->BRR = (0x119) ; // 256000 Baud
	//USART1->BRR = (0x8C)  ; // 512000 Baud
	//USART1->BRR = (0x46)  ; // 1024000 Baud
	//USART1->BRR = (0x23)  ; // 2048000 Baud
  //USART1->BRR = (0x18)  ; // 3000000 Baud (3 MHz, max speed that HTerm can get, non-standard speed)
	
	
	USART1->CR1 |= USART_CR1_TE; //transmitter enable
	USART1->CR1 |= USART_CR1_RE; //receiver enable
	USART1->CR1 |= USART_CR1_UE; //usart enable
}

void printMsg(char *msg, ...)
{
	//char buff[120]; //was 80
	va_list args;
	va_start(args,msg); 
	vsprintf(buff,msg,args);

	for(int i=0;i<strlen(buff);i++)
	{
	  USART1->DR = buff[i];
	  while(!(USART1->SR & USART_SR_TXE)); //wait for TXE, 1 = data transferred
  }
}
#ifndef printMsg_h
#define printMsg_h

extern int len;
extern char buff[];
//char buff[];

void usart_1_enable(void);
void printMsg(char *msg, ...);

#endif
void delay(unsigned long cycles)
{
  while(cycles >0)
	{
		asm("nop");asm("nop");asm("nop");asm("nop");asm("nop");asm("nop");asm("nop");asm("nop");
		asm("nop");asm("nop");asm("nop");asm("nop");asm("nop");asm("nop");asm("nop");asm("nop");
		asm("nop");asm("nop");asm("nop");asm("nop");asm("nop");asm("nop");asm("nop");asm("nop");
		asm("nop");asm("nop");asm("nop");asm("nop");asm("nop");asm("nop");asm("nop");asm("nop");
		asm("nop");asm("nop");asm("nop");  //to get 1 uS if delay(1)
  cycles--; 
	}
}
#ifndef delayUs_h
#define delayUs_h

extern void delay(unsigned long cycles);

#endif

Copy/paste all codes and save in the same directory for Keil. I am not sure but I think the same codes can work in other editors/compilers/assemblers, but I am not familiar with those.

STM32 I2C Scanner

I2C scanner for STM32f10x series

I2C scanner is fairly simple, yet fast and effective way to find whatever device you put onto I2C bus. Some devices (boards) comes with clear designation on the PCB, some with misleading designation – address is shifted to the left, so for example OLED display typical address is 0x3C/0x3D (depends of address selector jumper), but shifted to the left by 1 bit is 0x78 or 0x7A respectively. They made it as if zero bit is inserted at LSB place so that you ‘just’ send it as-is. But that is bad practice. Rather make your own shifting routine and insert 1 or 0, whether you want to read or write at this address.

Example:

scannerThe code is even simpler:

/* Part of the code, will not work alone !!! */

void twiScan(void)
{		int a=0; 
	 	for (uint8_t i=0;i<128;i++)
   {
			I2C1->CR1 |= I2C_CR1_START;
			while(!(I2C1->SR1 & I2C_SR1_SB));
			I2C1->DR=(i<<1|0); 
			while(!(I2C1->SR1)|!(I2C1->SR2)){}; 
			I2C1->CR1 |= I2C_CR1_STOP; 
			delay(100);//minium wait time is 40 uS, but for sure, leave it 100 uS
			a=(I2C1->SR1&I2C_SR1_ADDR);
			if (a==2)
		 {
				printMsg("Found I2C device at adress 0x%X (hexadecimal), or %d (decimal)\n",i,i);
		 }
	 }
}

Whole thing scan all 127 addresses in 45 mS.

Here is how looks whole packet with six addresses found. After each address found, there is 5.5 mS delay until timeout.:

scanner

Almost standard wire.c library

Since I am beginner, I just begin to make few more or less standard libraries for STM32f10x series. Right now there are three functions in wire.c; twiScan(), twiSend(), and twiReceive(). So far I did not found need for anything else, but that may change, so stay tuned. Since I have none of other MCU that has different set of registers with also different syntax for those. Here is complete thing with example of main.c code that does nothing except scan.:

#include "stm32f10x.h"
#include "printMsg.h"
#include "wire.h"
#include "delayUs.h"

int main()
{
  usart_1_enable(); //enabling printMsg();
  twiEnable();//enabling two wire interface, IIC or I2C
  twiScan();//before anything else, lets check which devices are on the bus, 
}

Implemented in wire.c with wireSend() and wireReceive() functions:

/* Two Wire Interface, I2C (or IIC), here will be called 'twi', and we have
   only twiEnable(), twiSend() and twiReceive(). The twiSend() function is 
	 fairly simple, we just send address of the device shifted to the left by
	 1 bit, or-red | zero (0) at free space that tell I2C bus it is for write operation.
	 The receive twiReceive() function works by sending address also shifted left
	 one bit with logic or | zero (0) at empty bit (LSB), but then we must send command 
	 to the device depending what device has. After command, we stop (although
	 we can remove STOP condition and continue to "repeated start", then we
	 must change bit after address of the device, now it is one (1) that tells
	 I2C bus we want to read. If we try only read from some address, device
	 don't know what to send. So we must first issue command, then read. For
	 specific command set read datasheet of particular device - it is different
	 for all different devices. More on my website: http://wp.me/p7jxwp-nD */

#include "stm32f10x.h"
#include "delayUs.h"
#include "wire.h"
#include "printMsg.h"

void twiEnable(void) 
{
  //just set all registries, but NOT START condition - execute once in main.c
	RCC->APB2ENR |= RCC_APB2ENR_IOPBEN | RCC_APB2ENR_AFIOEN; //B port enabled, alternate function 
	RCC->APB1ENR |= RCC_APB1ENR_I2C1EN; //I2C 1 enabled 
	GPIOB->CRL = 0xFF000000;// setting just pins B7 (SDA) and B6 (SCL), while leaving the rest intact 50 MHz!
	I2C1->CR2 |= 50; // GPIO clock freq=50 MHz MUST !!! be equal APB frequency (GPIO, 2, 10 or 50 MHz)
	I2C1->CCR |= I2C_CCR_FS; //fast mode
	I2C1->CCR |= 30; //not sure for 400 000 - (10= 1.2 MHz, 15=800 kHz, 30=400 kHz)
	I2C1->TRISE |= 51; // maximum rise time is 1000 nS
	I2C1->CR1 |= I2C_CR1_PE; 
}

void twiScan(void)
{		int a=0; 
	 	for (uint8_t i=0;i<128;i++)
   {
			I2C1->CR1 |= I2C_CR1_START;
			while(!(I2C1->SR1 & I2C_SR1_SB));
			I2C1->DR=(i<<1|0); 
			while(!(I2C1->SR1)|!(I2C1->SR2)){}; 
			I2C1->CR1 |= I2C_CR1_STOP; 
			delay(100);//minium wait time is 40 uS, but for sure, leave it 100 uS
			a=(I2C1->SR1&I2C_SR1_ADDR);
			if (a==2)
		 {
				printMsg("Found I2C device at adress 0x%X (hexadecimal), or %d (decimal)\n",i,i);
		 }
	 }
}
	
/* Command or commands, or sending bytes, just the same name of the variable 'command' */
void twiSend(uint8_t address, uint8_t command, uint8_t length)
{
	I2C1->CR1 |= I2C_CR1_START; //START condition 
	while(!(I2C1->SR1 & I2C_SR1_SB));
	I2C1->DR=(address<<1|0); //sending address of the device, 0 = sending
  while(!(I2C1->SR1 & I2C_SR1_ADDR)|!(I2C1->SR2));		
	I2C1->DR=command; //filling data register with byte, if single - command, multiple - command(s) and data
	for (uint8_t i=0;i<length;i++)
	{ 
		I2C1->DR=buffer[i]; //filling buffer with command or data
		delay(60);
	}
	I2C1->CR1 |= I2C_CR1_STOP;
}

void twiReceive(uint8_t address, uint8_t command, uint8_t length) 
{
	I2C1->CR1 |= I2C_CR1_ACK;
  I2C1->CR1 |= I2C_CR1_START; //start pulse 
	while(!(I2C1->SR1 & I2C_SR1_SB));
	I2C1->DR=(address<<1|0); //sending address of the device, 0 = sending
	while(!(I2C1->SR1 & I2C_SR1_ADDR)|!(I2C1->SR2 & I2C_SR2_BUSY));
	I2C1->DR=command; //sending command to the device in order to request data
	I2C1->CR1 |= I2C_CR1_START; //REPEATED START condition to change from sending address + command to receive data
	while(!(I2C1->SR1 & I2C_SR1_SB));
	I2C1->DR=(address<<1|1); //sending address of the device, 1 = reading 
	while(!(I2C1->SR1 & I2C_SR1_ADDR)|!(I2C1->SR2));
	
if (length==1)  //receiving single byte, N=1
	{
		while(!(I2C1->SR1)|!(I2C1->SR2));
		I2C1->CR1 &= ~I2C_CR1_ACK; //this will send later NAK (not acknowledged) to signal it is last byte
		I2C1->CR1 |= I2C_CR1_STOP; //issuing STOP condition before (!) reading byte
		buffer[0]=I2C1->DR; //single byte is read AFTER NAK (!) and STOP condition
	} 
	if (length==2) //receiving two bytes, N=2
	{
		while(!(I2C1->SR1)|!(I2C1->SR2));
		I2C1->CR1 &= ~I2C_CR1_ACK; //this will send later NAK (not acknowledged) before last byte
    I2C1->CR1 |= I2C_CR1_STOP;
		buffer[0]=I2C1->DR; //reading N-1 byte, next to last byte is in DR, last one still in shift register
		while(!(I2C1->SR1 & I2C_SR1_RXNE)|!(I2C1->SR2));
		buffer[1]=I2C1->DR; //read last N byte now available 
	} 
  if (length>2) //receiving more than two bytes, N>2
	{
		
	  for (uint8_t i=0;i<length;i++)
	  { 
			                     
		  if (i<(length-3))      // if it is not N-2, then read all bytes
			{
				while(!(I2C1->SR1 & I2C_SR1_RXNE)|!(I2C1->SR2));
				buffer[i]=I2C1->DR;  
			}
		  else if (i==length-3) // if it is N-2 then read 
			{
				while(!(I2C1->SR1)|!(I2C1->SR2));
				buffer[i]=I2C1->DR; 
				while(!(I2C1->SR1 & I2C_SR1_RXNE)|!(I2C1->SR2));
				I2C1->CR1 &= ~I2C_CR1_ACK; //this will send later NAK (not acknowledged) before last byte
				I2C1->CR1 |= I2C_CR1_STOP;
			}
	    else if (i==length-2) // if it is N-1 then read
			{
				while(!(I2C1->SR1 & I2C_SR1_RXNE)|!(I2C1->SR2));
				buffer[i]=I2C1->DR; 
			}
			else if (i==length-1) // else it is N byte 
			{
				while(!(I2C1->SR1 & I2C_SR1_RXNE)|!(I2C1->SR2)){};
		    buffer[i]=I2C1->DR;  
			}
    } 
 }
}
#ifndef wire_h
#define wire_h

#include <stdint.h>

extern uint8_t  address, command, length; 
extern uint8_t  buffer[];
extern uint8_t  status1;
extern uint8_t  status2;

void twiEnable(void);
void twiScan(void);
void twiSend(uint8_t address, uint8_t command, uint8_t length);
void twiReceive(uint8_t address, uint8_t command, uint8_t length);


#endif
#include "stm32f10x.h"
#include "stdint.h"
#include <stdio.h>
#include "stdarg.h"
#include "string.h"
#include "printMsg.h"

char buff[256];

void usart_1_enable(void)
{
  //enabling pin A9 for alternating funct. for uart/usart
  RCC->APB2ENR |= RCC_APB2ENR_IOPAEN | RCC_APB2ENR_AFIOEN | RCC_APB2ENR_USART1EN; //clock to GPIO A enabled, port A(2), alt.funct.en(0), usart1 clock enabled(14)
	GPIOA->CRH |= GPIO_CRH_CNF9_1 | GPIO_CRH_MODE9_0 | GPIO_CRH_MODE9_1; //port A9
	GPIOA->CRH &= ~GPIO_CRH_CNF9_0; //port A9
	GPIOA->CRH &= ~(GPIO_CRH_MODE10_0|GPIO_CRH_MODE10_1); //port A10 is RX
	GPIOA->CRH |= GPIO_CRH_CNF10_0; //port A10 is RX
	
	//GPIOA->CRH = 0x444444B4; // A9 is alternate output, 50 MHz, push-pull - not this time short version (!)
	//clkPer/(baudRx_16bit)=72MHZ/9600 = 7500 = 0x1D4C
	/* Remove comment line for speed that you want to use*/
	//USART1->BRR = (0xEA60); //   1200 Baud
	//USART1->BRR = (0x7530); //   2400 Baud
	//USART1->BRR = (0x3A98); //   4800 Baud
	//USART1->BRR = (0x1D4C); //   9600 Baud
	//USART1->BRR = (0x1388); //  14400 Baud
	//USART1->BRR = (0xEA6) ; //  19200 Baud
	//USART1->BRR = (0x9c4) ; //  28800 Baud
	//USART1->BRR = (0x753) ; //  38400 Baud
	//USART1->BRR = (0x505) ; //  56000 Baud
	//USART1->BRR = (0x4E2) ; //  57600 Baud
	USART1->BRR = (0x271) ; // 115200 Baud
	//USART1->BRR = (0x232) ; // 128000 Baud
	//USART1->BRR = (0x119) ; // 256000 Baud
	//USART1->BRR = (0x8C)  ; // 512000 Baud
	//USART1->BRR = (0x46)  ; // 1024000 Baud
	//USART1->BRR = (0x23)  ; // 2048000 Baud
  //USART1->BRR = (0x18)  ; // 3000000 Baud (3 MHz, max speed that HTerm can get, non-standard speed)
	
	
	USART1->CR1 |= USART_CR1_TE; //transmitter enable
	USART1->CR1 |= USART_CR1_RE; //receiver enable
	USART1->CR1 |= USART_CR1_UE; //usart enable
}

void printMsg(char *msg, ...)
{
	//char buff[120]; //was 80
	va_list args;
	va_start(args,msg); 
	vsprintf(buff,msg,args);

	for(int i=0;i<strlen(buff);i++)
	{
	  USART1->DR = buff[i];
	  while(!(USART1->SR & USART_SR_TXE)); //wait for TXE, 1 = data transferred
  }
}
#ifndef printMsg_h
#define printMsg_h

extern int len;
extern char buff[];
//char buff[];

void usart_1_enable(void);
void printMsg(char *msg, ...);

#endif
void delay(unsigned long cycles)
{
  while(cycles >0)
	{
		asm("nop");asm("nop");asm("nop");asm("nop");asm("nop");asm("nop");asm("nop");asm("nop");
		asm("nop");asm("nop");asm("nop");asm("nop");asm("nop");asm("nop");asm("nop");asm("nop");
		asm("nop");asm("nop");asm("nop");asm("nop");asm("nop");asm("nop");asm("nop");asm("nop");
		asm("nop");asm("nop");asm("nop");asm("nop");asm("nop");asm("nop");asm("nop");asm("nop");
		asm("nop");asm("nop");asm("nop");  //to get 1 uS if delay(1)
  cycles--; 
	}
}
#ifndef delayUs_h
#define delayUs_h

extern void delay(unsigned long cycles);

#endif

That is all. Happy scanning! 😀