commit before large work

This commit is contained in:
eddyem 2015-01-26 11:30:25 +03:00
parent 9b855489d5
commit 4ce1ca9c71
2 changed files with 522 additions and 0 deletions

103
with_opencm3/STM32_PINS Normal file
View File

@ -0,0 +1,103 @@
Functional map of MCU pins
# name functionality
001 PE2 DIR_3 direction of steppers' rotation
002 PE3 DIR_4
003 PE4 DIR_5
004 PE5 POW3 Turn ON/OFF power switch POW_LOAD
005 PE6 DG_FEEDBACK feedback from power switch POW_LOAD (+10..12V)
006 VBAT -
007 PC13 -
008 PC14 -
009 PC15 -
010 VSS GND
011 VDD +3.3V
012 OSC_IN 8MHz in
013 OSC_OUT 8MHz out
014 NRST Reset
015 PC0 SHTR Shutter on pulse
016 PC1 SHTR_FB Error signal from shutter H-bridge
017 PC2 POW0 Shutter polarity (open/close)
018 PC3 -
019 VSSA 0v analog
020 VREF- ref (0v)
021 VREF+ ref (+3.3v)
022 VDDA +3.3V analog
023 PA0 U10_ADC 10..12V voltage control
024 PA1 U36_ADC 36V voltage control
025 PA2 1WIRE_TX 1-wire interface
026 PA3 1WIRE_RX
027 VSS GND
028 VDD +3.3V
029 PA4 ADC7\
030 PA5 ADC6 |
031 PA6 ADC5 |
032 PA7 ADC4 | ADC 12bit input channels (TRD)
033 PC4 ADC3 |
034 PC5 ADC2 |
035 PB0 ADC1 |
036 PB1 ADC0/
037 BOOT1 BOOT 100k resistor to GND
038 PE7 EN1 \
039 PE8 EN2 |
040 PE9 EN3 | enable Xth stepper motor
041 PE10 EN4 |
042 PE11 EN5 /
043 PE12 POW2\
044 PE13 POW1/ Power load (10..12V, pull-down)
045 PE14 -
046 PE15 -
047 PB10 USART3_TX RS-232 (master)
048 PB11 USART3_RX
049 VSS GND
050 VDD +3.3V
051 PB12 -
052 SPI2_SCK \
053 SPI2_MISO | External SPI connection (at edge of the board)
054 SPI2_MOSI /
055 PD8 -
056 PD9 -
057 PD10 EXT0\
058 PD11 EXT1 | ADG506 address selection
059 PD12 EXT2 | or custom external ports
060 PD13 EXT3/
061 PD14 -
062 PD15 TIM2 timer for motors 4&5
063 PC6 TIM1 timer for stepper motors 1..3
064 PC7 \ LS1 Linear stage 1 (long) DOWN end-switch
065 PC8 / Linear stage 1 (long) UP end-switch
066 PC9 \ LS2 Linear stage 2 (short) DOWN end-switch
067 PA8 / Linear stage 2 (short) UP end-switch
068 PA9 BOOT_TX \ UART1 (slave): boot + ext UART
069 PA10 BOOT_RX /
070 PA11 USB_DM USB data-
071 PA12 USB_DP USB data+
072 PA13 -
073 NC -
074 VSS GND
075 VDD +3.3V
076 PA14 -
077 PA15 -
078 PC10 USB_POWER +3V when USB connected
079 PC11 USB_DISC software USB disconnection (low lewel for n-channel VT1, high level for pnp bipolar or p-channel MOSFET)
080 PC12 -
081 PD0 \
082 PD1 | Tur1 Slits turret Hall sensors
083 PD2 |
084 PD3 /
085 PD4 \
086 PD5 | Tur2 Middle filters turret Hall sensors
087 PD6 /
088 PD7 Tur3_0 Upper filters turret Hall 0
089 SPI1_SCK \
090 SPI1_MISO | SPI connection (near USB connector)
091 SPI1_MOSI/I2C_SMBAI/
092 PB6 Tur3_1 \ Upper filters turret Hall 1,2
093 PB7 Tur3_2 /
094 BOOT BOOT Button to boot from bootloader
095 I2C_SCL/CANRX \ External CAN connection (or I2S, etc)
096 I2C_SDA/CANTX /
097 PE0 DIR_1 direction of SM 1,2
098 PE1 DIR_2
099 VSS GND
100 VDD +3.3V

View File

@ -0,0 +1,419 @@
/*
* hardware_ini.c - functions for HW initialisation
*
* Copyright 2014 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*/
/*
* All hardware-dependent initialisation & definition should be placed here
* and in hardware_ini.h
*
*/
#include "main.h"
#include "hardware_ini.h"
#include "onewire.h"
volatile uint16_t ADC_value[8]; // ADC DMA value
/*
* Configure SPI ports
*/
/*
* SPI1 remapped:
* SCK - PB3
* MISO - PB4
* MOSI - PB5
*/
void SPI1_init(){
// enable AFIO & other clocking
rcc_peripheral_enable_clock(&RCC_APB2ENR,
RCC_APB2ENR_SPI1EN | RCC_APB2ENR_AFIOEN | RCC_APB2ENR_IOPBEN);
// remap SPI1 (change pins from PA5..7 to PB3..5); also turn off JTAG
gpio_primary_remap(AFIO_MAPR_SWJ_CFG_JTAG_OFF_SW_OFF, AFIO_MAPR_SPI1_REMAP);
// SCK, MOSI - push-pull output
gpio_set_mode(GPIO_BANK_SPI1_RE_SCK, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_SPI1_RE_SCK);
gpio_set_mode(GPIO_BANK_SPI1_RE_MOSI, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_SPI1_RE_MOSI);
// MISO - opendrain in
gpio_set_mode(GPIO_BANK_SPI1_RE_MISO, GPIO_MODE_INPUT, GPIO_CNF_INPUT_FLOAT, GPIO_SPI1_RE_MISO);
spi_reset(SPI1);
/* Set up SPI in Master mode with:
* Clock baud rate: 1/128 of peripheral clock frequency (APB2, 72MHz)
* Clock polarity: Idle High
* Clock phase: Data valid on 2nd clock pulse
* Data frame format: 8-bit
* Frame format: MSB First
*/
spi_init_master(SPI1, SPI_CR1_BAUDRATE_FPCLK_DIV_128, SPI_CR1_CPOL_CLK_TO_1_WHEN_IDLE,
SPI_CR1_CPHA_CLK_TRANSITION_2, SPI_CR1_DFF_8BIT, SPI_CR1_MSBFIRST);
nvic_enable_irq(NVIC_SPI1_IRQ); // enable SPI interrupt
}
/*
* SPI2:
* SCK - PB13
* MISO - PB14
* MOSI - PB15
*/
void SPI2_init(){
// turn on clocking
//rcc_periph_clock_enable(RCC_SPI2 | RCC_GPIOB);
rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_SPI2EN);
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_AFIOEN | RCC_APB2ENR_IOPBEN);
// SCK, MOSI - push-pull output
gpio_set_mode(GPIO_BANK_SPI2_SCK, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_SPI2_SCK);
gpio_set_mode(GPIO_BANK_SPI2_MOSI, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_SPI2_MOSI);
// MISO - opendrain in
gpio_set_mode(GPIO_BANK_SPI2_MISO, GPIO_MODE_INPUT, GPIO_CNF_INPUT_FLOAT, GPIO_SPI2_MISO);
spi_reset(SPI2);
/* Set up SPI in Master mode with:
* Clock baud rate: 1/64 of peripheral clock frequency (APB1, 36MHz)
* Clock polarity: Idle High
* Clock phase: Data valid on 2nd clock pulse
* Data frame format: 8-bit
* Frame format: MSB First
*/
spi_init_master(SPI2, SPI_CR1_BAUDRATE_FPCLK_DIV_64, SPI_CR1_CPOL_CLK_TO_1_WHEN_IDLE,
SPI_CR1_CPHA_CLK_TRANSITION_2, SPI_CR1_DFF_8BIT, SPI_CR1_MSBFIRST);
nvic_enable_irq(NVIC_SPI2_IRQ); // enable SPI interrupt
}
/**
* GPIO initialisaion: clocking + pins setup
*/
void GPIO_init(){
/* rcc_periph_clock_enable(RCC_AFIO);
rcc_periph_clock_enable(RCC_SPI1);
rcc_periph_clock_enable(RCC_GPIOC);*/
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN |
RCC_APB2ENR_IOPBEN | RCC_APB2ENR_IOPCEN | RCC_APB2ENR_IOPDEN |
RCC_APB2ENR_IOPEEN);
// USB_DISC: push-pull
gpio_set_mode(USB_DISC_PORT, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, USB_DISC_PIN);
// USB_POWER: open drain, externall pull down with R7 (22k)
gpio_set_mode(USB_POWER_PORT, GPIO_MODE_INPUT,
GPIO_CNF_INPUT_FLOAT, USB_POWER_PIN);
// AD7794 addr + en
gpio_set_mode(ADC_ADDR_PORT, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, ADC_ADDR_MASK | ADC_EN_PIN); // ADDRESS: PD10..12; EN: PD13
gpio_clear(ADC_ADDR_PORT, ADC_ADDR_MASK | ADC_EN_PIN); // clear address & turn switch off
}
/*
* SysTick used for system timer with period of 1ms
*/
void SysTick_init(){
systick_set_clocksource(STK_CSR_CLKSOURCE_AHB_DIV8); // Systyck: 72/8=9MHz
systick_set_reload(8999); // 9000 pulses: 1kHz
systick_interrupt_enable();
systick_counter_enable();
}
/*
* Due to inconvenient pins position on STM32F103VxT6 I had to make this strange location:
* my channel # -> ADC1/2 channel #
* 0 -> 9 PB1
* 1 -> 8 PB0
* 2 -> 15 PC5
* 3 -> 14 PC4
* 4 -> 7 PA7
* 5 -> 6 PA6
* 6 -> 5 PA5
* 7 -> 4 PA4
*/
uint8_t adc_channel_array[16] = {9,8,15,14,7,6,5,4};
#define ADC_CHANNELS_NUMBER 8
/**
* Turn on ADC DMA for filling temperatures buffer
*/
void adc_dma_on(){
// first configure DMA1 Channel1 (ADC1)
dma_channel_reset(DMA1, DMA_CHANNEL1); //DMA_DeInit(DMA1_Channel1);
dma_set_peripheral_address(DMA1, DMA_CHANNEL1, (uint32_t) &(ADC_DR(ADC1))); // DMA_InitStructure.DMA_PeripheralBaseAddr = ADC1_DR_Address;
dma_set_memory_address(DMA1, DMA_CHANNEL1, (uint32_t) ADC_value); // DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)&ADC_value;
dma_set_number_of_data(DMA1, DMA_CHANNEL1, ADC_CHANNELS_NUMBER); // DMA_InitStructure.DMA_BufferSize = 1;
dma_set_read_from_peripheral(DMA1, DMA_CHANNEL1); // DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
dma_enable_memory_increment_mode(DMA1, DMA_CHANNEL1); // DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Disable;
dma_disable_peripheral_increment_mode(DMA1, DMA_CHANNEL1); // DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
dma_set_peripheral_size(DMA1, DMA_CHANNEL1, DMA_CCR_PSIZE_16BIT); // DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord;
dma_set_memory_size(DMA1, DMA_CHANNEL1, DMA_CCR_MSIZE_16BIT); // DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord;
dma_enable_circular_mode(DMA1, DMA_CHANNEL1); // DMA_InitStructure.DMA_Mode = DMA_Mode_Circular; DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
dma_set_priority(DMA1, DMA_CHANNEL1, DMA_CCR_PL_HIGH); // DMA_InitStructure.DMA_Priority = DMA_Priority_High;
nvic_disable_irq(NVIC_DMA1_CHANNEL1_IRQ);
dma_disable_transfer_error_interrupt(DMA1, DMA_CHANNEL1);
dma_disable_transfer_complete_interrupt(DMA1, DMA_CHANNEL1);
dma_enable_channel(DMA1, DMA_CHANNEL1); // DMA_Cmd(DMA1_Channel1, ENABLE);
}
void ADC_init(){
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_ADC1EN); // enable clocking
rcc_periph_clock_enable(RCC_ADC1);
rcc_set_adcpre(RCC_CFGR_ADCPRE_PCLK2_DIV4);
rcc_periph_clock_enable(RCC_GPIOA | RCC_GPIOB | RCC_GPIOC); // clocking for ADC ports
// channels 4-7: PA7-PA4
gpio_set_mode(GPIOA, GPIO_MODE_INPUT, GPIO_CNF_INPUT_ANALOG, GPIO4|GPIO5|GPIO6|GPIO7);
// channels 0,1: PB1, PB0
gpio_set_mode(GPIOB, GPIO_MODE_INPUT, GPIO_CNF_INPUT_ANALOG, GPIO0|GPIO1);
// channels 2,3: PC5, PC4
gpio_set_mode(GPIOC, GPIO_MODE_INPUT, GPIO_CNF_INPUT_ANALOG, GPIO4|GPIO5);
// Make sure the ADC doesn't run during config
adc_off(ADC1);
rcc_periph_clock_enable(RCC_DMA1);
adc_dma_on();
// Configure ADC as continuous scan mode with DMA
adc_set_dual_mode(ADC_CR1_DUALMOD_IND); // ADC_InitStructure.ADC_Mode = ADC_Mode_Independent;
adc_enable_scan_mode(ADC1); // ADC_InitStructure.ADC_ScanConvMode = ENABLE;
adc_set_continuous_conversion_mode(ADC1); // ADC_InitStructure.ADC_ContinuousConvMode = ENABLE;
adc_disable_external_trigger_regular(ADC1); // ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_None;
adc_set_right_aligned(ADC1); // ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right;
adc_set_sample_time_on_all_channels(ADC1, ADC_SMPR_SMP_239DOT5CYC); // ADC_SampleTime_239Cycles5
//adc_set_sample_time(ADC1, ADC_CHANNEL8, ADC_SMPR_SMP_239DOT5CYC); // ADC_RegularChannelConfig(ADC1, ADC_Channel_8, 1, ADC_SampleTime_239Cycles5);
adc_enable_dma(ADC1); // ADC_DMACmd(ADC1, ENABLE);
adc_power_on(ADC1); // ADC_Cmd(ADC1, ENABLE);
}
/**
* Starts ADC calibration & after it runs ADC in continuous conversion mode
* First call ADC_init(), than wait a little and call this function
*/
void ADC_calibrate_and_start(){
adc_set_regular_sequence(ADC1, ADC_CHANNELS_NUMBER, adc_channel_array);
adc_reset_calibration(ADC1);
adc_calibration(ADC1);
adc_start_conversion_regular(ADC1); // ADC_SoftwareStartConvCmd(ADC1, ENABLE);
adc_start_conversion_direct(ADC1);
}
uint16_t tim2_buff[TIM2_DMABUFF_SIZE];
uint16_t tim2_inbuff[TIM2_DMABUFF_SIZE];
int tum2buff_ctr = 0;
uint8_t ow_done = 1;
/**
* this function sends bits of ow_byte (LSB first) to 1-wire line
* @param ow_byte - byte to convert
* @param Nbits - number of bits to send
* @param ini - 1 to zero counter
*/
uint8_t OW_add_byte(_U_ uint8_t ow_byte, _U_ uint8_t Nbits, _U_ uint8_t ini){
uint8_t i, byte;
if(ini) tum2buff_ctr = 0;
if(Nbits == 0) return 0;
if(Nbits > 8) Nbits = 8;
for(i = 0; i < Nbits; i++){
if(ow_byte & 0x01){
byte = OW_1;
}else{
byte = OW_0;
}
tim2_buff[tum2buff_ctr++] = byte;
if(tum2buff_ctr == TIM2_DMABUFF_SIZE) return 0; // avoid buffer overflow
ow_byte = ow_byte >> 1;
}
return 1;
}
/**
* Fill output buffer with data from 1-wire
* @param start_idx - index from which to start (bit number)
* @param N - data length (in **bytes**)
* @outbuf - where to place data
*/
void read_from_OWbuf(_U_ uint8_t start_idx, _U_ uint8_t N, _U_ uint8_t *outbuf){
uint8_t i, j, last = start_idx + N * 8, byte;
if(last >= TIM2_DMABUFF_SIZE) last = TIM2_DMABUFF_SIZE;
for(i = start_idx; i < last;){
byte = 0;
for(j = 0; j < 8; j++){
byte >>= 1;
if(tim2_inbuff[i++] < OW_READ1)
byte |= 0x80;
}
*outbuf++ = byte;
}
}
// there's a mistake in opencm3, so redefine this if needed (TIM_CCMR2_CC3S_IN_TI1 -> TIM_CCMR2_CC3S_IN_TI4)
#ifndef TIM_CCMR2_CC3S_IN_TI4
#define TIM_CCMR2_CC3S_IN_TI4 (2)
#endif
void init_ow_dmatimer(){ // tim2_ch4 - PA3, no remap
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_OPENDRAIN, GPIO3);
rcc_periph_clock_enable(RCC_TIM2);
rcc_periph_clock_enable(RCC_DMA1);
timer_reset(TIM2);
// timers have frequency of 1MHz -- 1us for one step
// 36MHz of APB1
timer_set_mode(TIM2, TIM_CR1_CKD_CK_INT, TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP);
// 72MHz div 72 = 1MHz
TIM2_PSC = 71; // prescaler is (div - 1)
TIM2_CR1 &= ~(TIM_CR1_OPM | TIM_CR1_UDIS); // continuous mode & enable update events
TIM2_CR1 |= TIM_CR1_ARPE; // changing period immediately
TIM2_ARR = OW_BIT; // default period of timer
// PWM_OUT: TIM2_CH4; capture: TIM2_CH3
// PWM edge-aligned mode & enable preload for CCR4, CC3 takes input from TI4
TIM2_CCMR2 = TIM_CCMR2_OC4M_PWM1 | TIM_CCMR2_OC4PE | TIM_CCMR2_CC3S_IN_TI4;
TIM2_CCR4 = 0; // set output value to 1 by clearing CCR4
TIM2_EGR = TIM_EGR_UG; // update values of ARR & CCR4
// set low polarity for CC4, high for CC4 & enable CC4 out and CC3 in
TIM2_CCER = TIM_CCER_CC4P | TIM_CCER_CC4E | TIM_CCER_CC3E;
}
void run_dmatimer(){
ow_done = 0;
DMA1_IFCR = DMA_ISR_TEIF7|DMA_ISR_HTIF7|DMA_ISR_TCIF7|DMA_ISR_GIF7 |
DMA_ISR_TEIF1|DMA_ISR_HTIF1|DMA_ISR_TCIF1|DMA_ISR_GIF1; // clear flags
init_ow_dmatimer();
// TIM2_CH4 - DMA1, channel 7
dma_channel_reset(DMA1, DMA_CHANNEL7);
dma_set_peripheral_address(DMA1, DMA_CHANNEL7, (uint32_t) &(TIM_CCR4(TIM2)));
dma_set_read_from_memory(DMA1, DMA_CHANNEL7);
dma_enable_memory_increment_mode(DMA1, DMA_CHANNEL7);
dma_disable_peripheral_increment_mode(DMA1, DMA_CHANNEL7);
dma_set_peripheral_size(DMA1, DMA_CHANNEL7, DMA_CCR_PSIZE_16BIT);
dma_set_memory_size(DMA1, DMA_CHANNEL7, DMA_CCR_MSIZE_16BIT);
dma_enable_transfer_error_interrupt(DMA1, DMA_CHANNEL7);
dma_enable_transfer_complete_interrupt(DMA1, DMA_CHANNEL7);
dma_set_memory_address(DMA1, DMA_CHANNEL7, (uint32_t)tim2_buff);
// TIM2_CH4 - DMA1, channel 7
dma_channel_reset(DMA1, DMA_CHANNEL1);
dma_set_peripheral_address(DMA1, DMA_CHANNEL1, (uint32_t) &(TIM_CCR3(TIM2)));
dma_set_read_from_peripheral(DMA1, DMA_CHANNEL1);
dma_enable_memory_increment_mode(DMA1, DMA_CHANNEL1);
dma_disable_peripheral_increment_mode(DMA1, DMA_CHANNEL1);
dma_set_peripheral_size(DMA1, DMA_CHANNEL1, DMA_CCR_PSIZE_16BIT);
dma_set_memory_size(DMA1, DMA_CHANNEL1, DMA_CCR_MSIZE_16BIT);
dma_enable_transfer_error_interrupt(DMA1, DMA_CHANNEL1);
dma_enable_transfer_complete_interrupt(DMA1, DMA_CHANNEL1);
nvic_enable_irq(NVIC_DMA1_CHANNEL1_IRQ);
nvic_enable_irq(NVIC_DMA1_CHANNEL7_IRQ); // enable dma1_channel7_isr
TIM2_SR = 0; // clear all flags
TIM2_CR1 &= ~TIM_CR1_OPM; // continuous mode
timer_set_period(TIM2, OW_BIT); // bit length
timer_generate_event(TIM2, TIM_EGR_UG); // update values
dma_set_memory_address(DMA1, DMA_CHANNEL7, (uint32_t)tim2_buff);
dma_set_number_of_data(DMA1, DMA_CHANNEL7, tum2buff_ctr);
//for(i = 0; i < TIM2_DMABUFF_SIZE; i++) tim2_inbuff[i] = 0;
dma_set_memory_address(DMA1, DMA_CHANNEL1, (uint32_t) tim2_inbuff);
dma_set_number_of_data(DMA1, DMA_CHANNEL1, tum2buff_ctr);
dma_enable_channel(DMA1, DMA_CHANNEL7);
dma_enable_channel(DMA1, DMA_CHANNEL1);
timer_set_dma_on_compare_event(TIM2);
TIM2_CCER |= TIM_CCER_CC3E; // enable input capture
TIM2_DIER = TIM_DIER_CC4DE | TIM_DIER_CC3DE; // enable DMA events
// set low polarity, enable cc out & enable input capture
TIM2_CCER |= TIM_CCER_CC4P | TIM_CCER_CC4E | TIM_CCER_CC3E;
TIM2_CR1 |= TIM_CR1_CEN; // run timer
}
uint16_t rstat = 0, lastcc3;
void ow_reset(){
ow_done = 0;
rstat = 0;
TIM2_SR = 0; // clear all flags
TIM2_DIER = 0; // disable timer interrupts
TIM2_ARR = OW_RESET_TIME; // set period to 1ms
TIM2_CCR4 = OW_RESET; // zero pulse length
TIM2_EGR = TIM_EGR_UG; // update values of ARR & CCR4
TIM2_CR1 |= TIM_CR1_OPM | TIM_CR1_CEN; // we need only single pulse & run timer
TIM2_SR = 0; // clear update flag generated after timer's running
TIM2_DIER = TIM_DIER_UIE | TIM_DIER_CC3IE; // generate interrupts on update event & cc
nvic_enable_irq(NVIC_TIM2_IRQ);
}
void tim2_isr(){
if(TIM2_SR & TIM_SR_UIF){ // update interrupt
TIM2_SR &= ~TIM_SR_UIF; // clear flag
TIM2_DIER = 0; // disable all timer interrupts
TIM2_CCR4 = 0; // set output value to 1
TIM2_EGR |= TIM_EGR_UG; // generate update event to change value in CCR4
TIM2_CR1 &= ~TIM_CR1_CEN; // timer_disable_counter(TIM2);
nvic_disable_irq(NVIC_TIM2_IRQ);
ow_done = 1;
rstat = lastcc3;
print_int(rstat, lastsendfun);
MSG("\n");
}
if(TIM2_SR & TIM_SR_CC3IF){ // we need this interrupt to store CCR3 value
TIM2_SR = 0; // clear flag (we've manage TIM_SR_UIF before, so can simply do =0)
lastcc3 = TIM2_CCR3;
//TIM2_DIER &= ~TIM_DIER_CC3IE; // disable CCR3 interrupts
}
}
void dma1_channel7_isr(){
if(DMA1_ISR & DMA_ISR_TCIF7) {
DMA1_IFCR = DMA_IFCR_CTCIF7;
dma_disable_channel(DMA1, DMA_CHANNEL7);
timer_disable_irq(TIM2, TIM_DIER_CC4DE);
}else if(DMA1_ISR & DMA_ISR_TEIF7){
DMA1_IFCR = DMA_IFCR_CTEIF7;
MSG("out transfer error\n");
}
}
void dma1_channel1_isr(){
int i;
if(DMA1_ISR & DMA_ISR_TCIF1) {
DMA1_IFCR = DMA_IFCR_CTCIF1;
// TIM2_CCER &= ~TIM_CCER_CC4P; //timer_set_oc_polarity_high(TIM2, TIM_OC4);
TIM2_CR1 &= ~TIM_CR1_CEN; // timer_disable_counter(TIM2);
timer_disable_irq(TIM2, TIM_DIER_CC3DE);
// gpio_set(GPIOA, GPIO3);
dma_disable_channel(DMA1, DMA_CHANNEL1);
nvic_disable_irq(NVIC_DMA1_CHANNEL1_IRQ);
ow_done = 1;
for(i = 0; i < tum2buff_ctr; i++){
print_int(tim2_inbuff[i], lastsendfun);
MSG(" ");
}
MSG("\n");
}else if(DMA1_ISR & DMA_ISR_TEIF1){
DMA1_IFCR = DMA_IFCR_CTEIF1;
MSG("in transfer error\n");
}
}
uint8_t OW_get_reset_status(){
print_int(rstat, lastsendfun);
MSG("\n");
if(rstat < OW_PRESENT) return 0; // no devices
return 1;
}