16x16 square of neopixels for stm32f3 discovery board

Dependencies:   STM32F3-Discovery-minimal

Fork of neopixels by Martin Johnson

neopixel.c

Committer:
MartinJohnson
Date:
2018-05-07
Revision:
1:6ed7aa3c8efa
Parent:
0:d89511b21e3d

File content as of revision 1:6ed7aa3c8efa:


#include <stm32f30x.h>
#include <math.h>
#include "stm32f3_discovery_lsm303dlhc.h"
#include <stdio.h>
#include <stdlib.h>

#define PI 3.1415926f

#define WS2812_LED_STRIP_LENGTH 256
#define WS2812_BITS_PER_LED 24
#define WS2812_DELAY_BUFFER_LENGTH 42 // for 50us delay

#define BIT_COMPARE_1 17 // timer compare value for logical 1
#define BIT_COMPARE_0 9  // timer compare value for logical 0
#define WS2812_DATA_BUFFER_SIZE (WS2812_BITS_PER_LED * WS2812_LED_STRIP_LENGTH)

#define WS2812_DMA_BUFFER_SIZE (WS2812_DATA_BUFFER_SIZE + WS2812_DELAY_BUFFER_LENGTH)   // number of bytes needed is #LEDs * 24 bytes + 42 trailing bytes)


#define I2C_CR2_CLEAR_MASK ~(I2C_CR2_SADD | I2C_CR2_NBYTES | I2C_CR2_RELOAD | I2C_CR2_AUTOEND | I2C_CR2_RD_WRN | I2C_CR2_START | I2C_CR2_STOP)

void i2cWrite(int address, int reg, int val) {
	while(I2C1->ISR & I2C_ISR_BUSY);
	I2C1->CR2 = (I2C1->CR2 & I2C_CR2_CLEAR_MASK) | I2C_CR2_RELOAD | I2C_CR2_START | (1<<16) | address;
	while(!(I2C1->ISR & I2C_ISR_TXIS));
	I2C1->TXDR=reg;
	while(!(I2C1->ISR & I2C_ISR_TCR));
	I2C1->CR2 = (I2C1->CR2 & I2C_CR2_CLEAR_MASK) | I2C_CR2_AUTOEND | (1<<16) | address;
	while(!(I2C1->ISR & I2C_ISR_TXIS));
	I2C1->TXDR=val;
	while(!(I2C1->ISR & I2C_ISR_STOPF));
	I2C1->ICR = I2C_ICR_STOPCF;
}

void i2cRead(int address, int reg, uint8_t *data, int nbytes) {
	while(I2C1->ISR & I2C_ISR_BUSY);
	I2C1->CR2 = (I2C1->CR2 & I2C_CR2_CLEAR_MASK) | I2C_CR2_START | (1<<16) | address;
	while(!(I2C1->ISR & I2C_ISR_TXIS));
	if(nbytes>1) reg |= 0x80;
	I2C1->TXDR=reg;
	while(!(I2C1->ISR & I2C_ISR_TC));
	I2C1->CR2 = (I2C1->CR2 & I2C_CR2_CLEAR_MASK) | I2C_CR2_AUTOEND | I2C_CR2_START | I2C_CR2_RD_WRN | (nbytes<<16) | address;
	while(nbytes--) {
		while(!(I2C1->ISR & I2C_ISR_RXNE));
		*data++=I2C1->RXDR;
	}
	while(!(I2C1->ISR & I2C_ISR_STOPF));
	I2C1->ICR = I2C_ICR_STOPCF;
}
#define GPIO_MODE_INPUT 0
#define GPIO_MODE_OUTPUT 1
#define GPIO_MODE_AF 2

#define GPIO_PULL_UP 1
#define GPIO_PULL_DOWN 2

#define GPIO_OUTPUT_PUSH_PULL 0

#define GPIO_SPEED_FAST 3

void gpio_set_mode(GPIO_TypeDef *g,int n,int mode) {
	n=n<<1;
	g->MODER = (g->MODER & ~(3<<n)) | (mode<<n);
}

void gpio_set_af(GPIO_TypeDef *g,int n,int af, int otype, int pupd, int speed) {
	int reg=n>>3;
	int pos=(n&7)*4;
	g->AFR[reg] = (g->AFR[reg] & ~(0xf<<pos)) | (af<<pos); // alt func
	pos=(n<<1);
	g->OSPEEDR = (g->OSPEEDR & ~(3<<pos)) | (speed<<pos);
	g->OTYPER = (g->OTYPER & ~(1<<n)) | (otype<<n);
	gpio_set_mode(g,n,GPIO_MODE_AF);
	g->PUPDR = (g->PUPDR & ~(3<<pos)) | (pupd<<pos);	
}
	
void i2cInit() {
  RCC->APB1ENR |= RCC_APB1ENR_I2C1EN;
  RCC->AHBENR |= RCC_AHBENR_GPIOBEN;
  // configure GPIOPB6 and 7
  gpio_set_af(GPIOB,6,4,GPIO_OUTPUT_PUSH_PULL,GPIO_PULL_DOWN,GPIO_SPEED_FAST);
  gpio_set_af(GPIOB,7,4,GPIO_OUTPUT_PUSH_PULL,GPIO_PULL_DOWN,GPIO_SPEED_FAST);

  I2C1->TIMINGR = 0x00902025;
  I2C1->CR1 |= I2C_CR1_PE;

}

void MemsConfig(void)
{
  i2cInit();
  i2cWrite(ACC_I2C_ADDRESS, LSM303DLHC_CTRL_REG1_A,LSM303DLHC_NORMAL_MODE | LSM303DLHC_ODR_50_HZ | LSM303DLHC_AXES_ENABLE);
  i2cWrite(ACC_I2C_ADDRESS, LSM303DLHC_CTRL_REG4_A,LSM303DLHC_FULLSCALE_2G | LSM303DLHC_BlockUpdate_Continous | LSM303DLHC_BLE_LSB | LSM303DLHC_HR_ENABLE);
  i2cWrite(ACC_I2C_ADDRESS, LSM303DLHC_CTRL_REG2_A,LSM303DLHC_HPM_NORMAL_MODE | LSM303DLHC_HPFCF_16 | LSM303DLHC_HPF_AOI1_DISABLE | LSM303DLHC_HPF_AOI2_DISABLE);
 
  i2cWrite(MAG_I2C_ADDRESS, LSM303DLHC_CRA_REG_M, LSM303DLHC_TEMPSENSOR_ENABLE | LSM303DLHC_ODR_30_HZ);
  i2cWrite(MAG_I2C_ADDRESS, LSM303DLHC_CRB_REG_M, LSM303DLHC_FS_8_1_GA);
  i2cWrite(MAG_I2C_ADDRESS, LSM303DLHC_MR_REG_M,LSM303DLHC_CONTINUOS_CONVERSION);
}

void ReadAccelerometer(int16_t * data) {  
	i2cRead(ACC_I2C_ADDRESS, LSM303DLHC_OUT_X_L_A, (uint8_t *)data, 6);
}

void ReadMagnetometer(int16_t * data) {
	i2cRead(MAG_I2C_ADDRESS, LSM303DLHC_OUT_X_L_M, (uint8_t *)data, 1);
	i2cRead(MAG_I2C_ADDRESS, LSM303DLHC_OUT_X_H_M, (uint8_t *)data+1, 1);
	i2cRead(MAG_I2C_ADDRESS, LSM303DLHC_OUT_Y_L_M, (uint8_t *)data+2, 1);
	i2cRead(MAG_I2C_ADDRESS, LSM303DLHC_OUT_Y_H_M, (uint8_t *)data+3, 1);
	i2cRead(MAG_I2C_ADDRESS, LSM303DLHC_OUT_Z_L_M, (uint8_t *)data+4, 1);
	i2cRead(MAG_I2C_ADDRESS, LSM303DLHC_OUT_Z_H_M, (uint8_t *)data+5, 1);
}

int ReadTemperature() {
	int t=0;
	i2cRead(MAG_I2C_ADDRESS, LSM303DLHC_TEMP_OUT_L_M, (uint8_t *)&t,1);
	i2cRead(MAG_I2C_ADDRESS, LSM303DLHC_TEMP_OUT_H_M, (uint8_t *)&t+1,1);
	return t/64;
}

static uint8_t ledStripDMABuffer[WS2812_DMA_BUFFER_SIZE];

static uint8_t WS2812LedDataTransferInProgress = 0;

volatile  unsigned	sysTiming;
volatile  unsigned  sysTicks = 0;

void sysDelayMs(unsigned dly) {
	sysTiming = dly;
	while (sysTiming > 0) __wfi();

}
void SysTick_Handler(void) {
        sysTicks++;
        if (sysTiming > 0) --sysTiming; 
}

void GPIO_init(void) {
    
    RCC->AHBENR |= RCC_AHBENR_GPIOAEN | RCC_AHBENR_GPIOBEN | RCC_AHBENR_GPIOEEN ;
    RCC->APB1ENR |= RCC_APB1ENR_PWREN | RCC_APB1ENR_TIM2EN;
    RCC->APB2ENR |= RCC_APB2ENR_SYSCFGEN | RCC_APB2ENR_TIM16EN;

	SysTick_Config((SystemCoreClock / 1000) -1 );
    
    gpio_set_af(GPIOB,8,1,GPIO_OUTPUT_PUSH_PULL,GPIO_PULL_UP,GPIO_SPEED_FAST);

    GPIOE->MODER = (GPIOE->MODER&0xffff) | 0x55550000; // output mode for PE8-15
	GPIOA->MODER = (GPIOA->MODER&0xfffffffc)  ; // input mode for PA0
	GPIOA->PUPDR = (GPIOA->PUPDR & ~0x3) | 0x2; // pull down (10)
}

void TIM_init(void)
{
	TIM16->CR1 &= ~TIM_CR1_CEN;
	TIM16->PSC=(uint16_t) (SystemCoreClock / 24000000) - 1;
	TIM16->CNT=0;
	TIM16->ARR=29;	// 24MHz/30=800KHz
	TIM16->CR1 |= TIM_CR1_CEN;
	
	// disable Capture and Compare 1
	TIM16->CCER &= ~TIM_CCER_CC1E;
	// set output compare 1 to PWM mode with preload
	TIM16->CCMR1 = (TIM16->CCMR1 & ~(TIM_CCMR1_OC1M | TIM_CCMR1_CC1S)) | TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_1 | TIM_CCMR1_OC1PE ;
	// enable Capture and Compare 1
	TIM16->CCER |= TIM_CCER_CC1E;
	// main output enable
    TIM16->BDTR |= TIM_BDTR_MOE; 
}

void DMA_init(void) {
    // enable DMA1 controller
    RCC->AHBENR |= RCC_AHBENR_DMA1EN;
    // direction = peripheral dest, memory inc, peripheral size=halfword, memory size=byte, priority level=high, transmission complete interrupt enabled
    DMA1_Channel3->CCR = DMA_CCR_DIR | DMA_CCR_MINC | DMA_CCR_PSIZE_0 | DMA_CCR_PL_1 | DMA_CCR_TCIE;
    // bytes to transfer
    DMA1_Channel3->CNDTR = WS2812_DMA_BUFFER_SIZE;
    // peripheral address
    DMA1_Channel3->CPAR =(uint32_t)&TIM16->CCR1;
    // memory address
    DMA1_Channel3->CMAR =(uint32_t)ledStripDMABuffer;
    // enable CC DMA for TIM16
    TIM16->DIER |= TIM_DIER_CC1DE;
	// configure NVIC
    NVIC->IP[DMA1_Channel3_IRQn]=16; // Interrupt Priority, lower is higher priority
	NVIC->ISER[DMA1_Channel3_IRQn >> 0x05] = 1 << (DMA1_Channel3_IRQn & 0x1F); // Interrupt enable
	
}

void WS2812LedStripDMAEnable(void) {
	// bytes to transfer
    DMA1_Channel3->CNDTR = WS2812_DMA_BUFFER_SIZE;                       
    TIM16->CNT=0;
    // start counter
    TIM16->CCER |= TIM_CCER_CC1E;
    // enable DMA
    DMA1_Channel3->CCR |= DMA_CCR_EN;
}

 void DMA1_Channel3_IRQHandler(void) {
    // if transfer complete
    if(DMA1->ISR & DMA_ISR_TCIF3) {
    	WS2812LedDataTransferInProgress = 0;
    	// disable DMA
    	DMA1_Channel3->CCR &= ~DMA_CCR_EN;
    	// clear flag
    	DMA1->IFCR = DMA_ISR_TCIF3;
    }
}

uint8_t *updateLEDDMABuffer(uint8_t *buffer, unsigned val) {
    for (int i=0;i<8;i++) {
        if ((val) & (0x80))    // data sent MSB first
        	*buffer++=BIT_COMPARE_1; // pwm level for 1
        else
        	*buffer++=BIT_COMPARE_0; // pwm level for 0
    	val=val<<1; // move to next bit
    }
    return buffer;
}

typedef struct  {
    uint8_t red;
    uint8_t green;
    uint8_t blue;
} rgb_struct;

static volatile rgb_struct rgbData[WS2812_LED_STRIP_LENGTH];

void WS2812UpdateStrip(void) {
    // wait until previous transfer completes
    while (WS2812LedDataTransferInProgress) __wfi();
    uint8_t *buffer=ledStripDMABuffer;
    for(int i=0;i<WS2812_LED_STRIP_LENGTH;i++) {
        buffer=updateLEDDMABuffer(buffer,rgbData[i].green);
        buffer=updateLEDDMABuffer(buffer,rgbData[i].red);
        buffer=updateLEDDMABuffer(buffer,rgbData[i].blue);
    }

    WS2812LedDataTransferInProgress = 1;
    WS2812LedStripDMAEnable();
}

extern volatile unsigned             sysTicks;
int rndseed=0;

void WS2812LedStripInit(void) {
    int i;
    for (i = 0; i < WS2812_DMA_BUFFER_SIZE; i++)
        ledStripDMABuffer[i] = 0;
    WS2812UpdateStrip();
}
static  short           AccBuffer[3] = {0};
static  short           MagBuffer[3] = {0};

int getheading() {
    /* Read Compass data */
    ReadMagnetometer(MagBuffer);
    ReadAccelerometer(AccBuffer);
    float fNormAcc, fSinRoll, fCosRoll, fSinPitch, fCosPitch = 0.0f, RollAng = 0.0f, PitchAng = 0.0f;
    float fTiltedX, fTiltedY = 0.0f;
    float HeadingValue;
    
    fNormAcc = sqrtf((AccBuffer[0] * AccBuffer[0]) + (AccBuffer[1] * AccBuffer[1]) +
                    (AccBuffer[2] * AccBuffer[2]));

    fSinRoll = -AccBuffer[1] / fNormAcc;
    fCosRoll = sqrtf(1.0f - (fSinRoll * fSinRoll));
    fSinPitch = AccBuffer[0] / fNormAcc;
    fCosPitch = sqrtf(1.0f - (fSinPitch * fSinPitch));
    if (fSinRoll > 0) {
        if (fCosRoll > 0) {
            RollAng = acos(fCosRoll) * 180 / PI;
        }
        else {
            RollAng = acos(fCosRoll) * 180 / PI + 180;
        }
    }
    else {
        if (fCosRoll > 0) {
            RollAng = acos(fCosRoll) * 180 / PI + 360;
        }
        else {
            RollAng = acos(fCosRoll) * 180 / PI + 180;
        }
    }
    if (fSinPitch > 0) {
        if (fCosPitch > 0) {
            PitchAng = acos(fCosPitch) * 180 / PI;
        }
        else {
            PitchAng = acos(fCosPitch) * 180 / PI + 180;
        }
    }
    else {
        if (fCosPitch > 0) {
            PitchAng = acos(fCosPitch) * 180 / PI + 360;
        }
        else {
            PitchAng = acos(fCosPitch) * 180 / PI + 180;
        }
    }

    if (RollAng >= 360) {
        RollAng = RollAng - 360;
    }

    if (PitchAng >= 360) {
        PitchAng = PitchAng - 360;
    }

    fTiltedX = MagBuffer[0] * fCosPitch + MagBuffer[2] * fSinPitch;
    fTiltedY = MagBuffer[0] * fSinRoll * fSinPitch + MagBuffer[1] * fCosRoll -
               MagBuffer[1] * fSinRoll * fCosPitch;

//    fTiltedX=fTiltedX/sqrt(fTiltedX*fTiltedX+fTiltedY*fTiltedY);
    HeadingValue = (float) ((atan2f( (float)fTiltedY, (float)fTiltedX)) * 180) / PI;

    if (HeadingValue < 0) {
        HeadingValue = HeadingValue + 360;
    }
    return HeadingValue;
}

int main(void) {
    uint8_t i = 0;
    int j=0;
    int delay=2000;
    int dch=-1;
    int dir=1;
    int btn=0;
    uint32_t rgb = 0x0ff0000ff;
    GPIO_init();
    DMA_init();
    TIM_init();
    MemsConfig();

    WS2812LedDataTransferInProgress = 0;
    WS2812LedStripInit();

	float yo=7.5,xo=7.5;
	float xs=1,ys=1;
	float offset=0;
	while(!(GPIOA->IDR & 1)) {    
		offset-=0.3f;
		//int heading = getheading();
		ReadAccelerometer(AccBuffer);
        int x=(int)AccBuffer[0]/32;
        int y=(int)AccBuffer[1]/32;
        ys=y/180.0+1;
        xs=x/180.0+1;

	    for (int i = 0; i < 256; i++) {
	        int y1=i/16;
	        int x1=i%16;
	        if(y1%2) x1=15-x1;
	        y1=15-y1;
	        
	        double d=(sqrt(abs(ys*(y1-yo)*(y1-yo)+xs*(x1-xo)*(x1-xo)))+offset)/4.0;
	        rgbData[i].red=(uint8_t)(round(4.0*sin(1.0299*d)+4.0)/1);
    		rgbData[i].green=(uint8_t)(round(4.0*cos(3.2235*d)+4.0)/1);
    		rgbData[i].blue=(uint8_t)(round(4.0*sin(5.1234*d)+4.0)/1);
		}
	    WS2812UpdateStrip();
		// wait 5ms
	    sysDelayMs(5);
	}

    while (GPIOA->IDR & 1) {
        int heading = getheading();
        int led = (heading * WS2812_LED_STRIP_LENGTH) / 360;
        int next = (led + 1) % WS2812_LED_STRIP_LENGTH;
        int v2 = (heading - (led * 360) / WS2812_LED_STRIP_LENGTH) * 10;
        int v1 = 225 - v2;
        
        rgbData[led].red = v1;
        rgbData[next].red = v2;

        WS2812UpdateStrip();
        // wait 15ms
        sysDelayMs(15);
        rgbData[led].red = 0;
        rgbData[next].red = 0;

    }
    
    while (1) { // flashing lights moving along the strip

		int NLIGHTS=32;
		i=j;
		for(int k=0;k<NLIGHTS;k++) {
	        rgbData[i].red = (rgb & 255)/8; // green
	        rgbData[i].green = ((rgb >> 8) & 255)/8; // red
	        rgbData[i].blue = ((rgb >> 16) & 255)/8; // blue
	        i=(i+WS2812_LED_STRIP_LENGTH/NLIGHTS)%WS2812_LED_STRIP_LENGTH;
        }

        WS2812UpdateStrip();
        sysDelayMs(delay/100);
        if((GPIOA->IDR & 1)==1 && btn==0)
            dir=-dir;
        btn=(GPIOA->IDR & 1);
        delay=delay+dch;
        if(delay<500 || delay>3000)
            dch=-dch;
        for(int k=0;k<WS2812_LED_STRIP_LENGTH;k++) {
        	rgbData[k].red = 0;
        	rgbData[k].green = 0;
        	rgbData[k].blue = 0;
        }

        ReadAccelerometer(AccBuffer);
        int y=(int)AccBuffer[1]/32;

        delay=10000-abs(y)*20;
        if(delay<0) delay=0;
        if(y<0)
            dir=1;
        else
            dir=-1;

        j=(j+dir+WS2812_LED_STRIP_LENGTH)%WS2812_LED_STRIP_LENGTH;
  
        rgb=(rgb<<1) /*^ (rand()&1 & rand()&1) ; */| (rgb>>24);

    }
}