spi.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2017, James Jackson
3  *
4  * All rights reserved.
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions are met:
8  *
9  * * Redistributions of source code must retain the above copyright notice, this
10  * list of conditions and the following disclaimer.
11  *
12  * * Redistributions in binary form must reproduce the above copyright notice,
13  * this list of conditions and the following disclaimer in the documentation
14  * and/or other materials provided with the distribution.
15  *
16  * * Neither the name of the copyright holder nor the names of its
17  * contributors may be used to endorse or promote products derived from
18  * this software without specific prior written permission.
19  *
20  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
21  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
22  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
23  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
24  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
25  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
26  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
27  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
28  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
29  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
30  */
31 
32 #include "spi.h"
33 
37 
38 static uint8_t dummy_buffer[256];
39 
41 {
42  SPI_InitTypeDef spi_init_struct;
43 
44  c_ = c;
45 
46  if (c_->dev == SPI1)
47  SPI1ptr = this;
48  else if (c_->dev == SPI2)
49  SPI2ptr = this;
50  else if (c_->dev == SPI3)
51  SPI3ptr = this;
52 
53  // Set the AF configuration for the other pins
57 
58  // Initialize other pins
62 
63  // Set up the SPI peripheral
66  spi_init_struct.SPI_Mode = SPI_Mode_Master;
67  spi_init_struct.SPI_DataSize = SPI_DataSize_8b;
68  spi_init_struct.SPI_CPOL = SPI_CPOL_High;
69  spi_init_struct.SPI_CPHA = SPI_CPHA_2Edge;
70  spi_init_struct.SPI_NSS = SPI_NSS_Soft;
71  spi_init_struct.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_64; // 42/64 = 0.65625 MHz SPI Clock
72  spi_init_struct.SPI_FirstBit = SPI_FirstBit_MSB;
73  spi_init_struct.SPI_CRCPolynomial = 7;
74  SPI_Init(c_->dev, &spi_init_struct);
76  SPI_Cmd(c_->dev, ENABLE);
77 
78  // Wait for any transfers to clear (this should be really short if at all)
80  ;
81  SPI_I2S_ReceiveData(c_->dev); // dummy read if needed
82 
83  // Configure the DMA
94  DMA_InitStructure_.DMA_PeripheralBaseAddr = reinterpret_cast<uint32_t>(&(c_->dev->DR));
97 
98  // Configure the Appropriate Interrupt Routine
99  NVIC_InitTypeDef NVIC_InitStruct;
100  NVIC_InitStruct.NVIC_IRQChannel = c_->DMA_IRQn;
101  NVIC_InitStruct.NVIC_IRQChannelCmd = ENABLE;
102  NVIC_InitStruct.NVIC_IRQChannelPreemptionPriority = 0x02;
103  NVIC_InitStruct.NVIC_IRQChannelSubPriority = 0x02;
104  NVIC_Init(&NVIC_InitStruct);
105 
106  transfer_cb_ = NULL;
107 }
108 
109 void SPI::set_divisor(uint16_t new_divisor)
110 {
111  SPI_Cmd(c_->dev, DISABLE);
112 
113  const uint16_t clearBRP = 0xFFC7;
114 
115  uint16_t temp = c_->dev->CR1;
116 
117  temp &= clearBRP;
118  switch (new_divisor)
119  {
120  case 2:
121  temp |= SPI_BaudRatePrescaler_2;
122  break;
123  case 4:
124  temp |= SPI_BaudRatePrescaler_4;
125  break;
126  case 8:
127  temp |= SPI_BaudRatePrescaler_8;
128  break;
129  case 16:
130  temp |= SPI_BaudRatePrescaler_16;
131  break;
132  case 32:
133  default:
134  temp |= SPI_BaudRatePrescaler_32;
135  break;
136  case 64:
137  temp |= SPI_BaudRatePrescaler_64;
138  break;
139  case 128:
141  break;
142  case 256:
144  break;
145  }
146  c_->dev->CR1 = temp;
147  SPI_Cmd(c_->dev, ENABLE);
148 }
149 
150 void SPI::enable(GPIO& cs)
151 {
152  cs.write(GPIO::LOW);
153 }
154 
156 {
157  cs.write(GPIO::HIGH);
158 }
159 
160 uint8_t SPI::transfer_byte(uint8_t data, GPIO* cs)
161 {
162  uint16_t spiTimeout;
163 
164  spiTimeout = 0x1000;
165 
166  if (cs != NULL)
167  enable(*cs);
168 
170  {
171  if ((--spiTimeout) == 0)
172  return false;
173  }
174 
175  SPI_I2S_SendData(c_->dev, data);
176 
177  spiTimeout = 0x1000;
178 
180  {
181  if ((--spiTimeout) == 0)
182  return false;
183  }
184 
185  if (cs)
186  disable(*cs);
187 
188  return static_cast<uint8_t>(SPI_I2S_ReceiveData(c_->dev));
189 }
190 
191 bool SPI::write(const uint8_t* out_data, uint32_t num_bytes, GPIO* cs)
192 {
193  busy_ = true;
194 
195  // Save Job parameters
197  out_buffer_ptr_ = (out_data == NULL) ? dummy_buffer : out_data;
198  cs_ = cs;
199  transfer_cb_ = NULL;
200  num_bytes_ = num_bytes;
201 
203  return true;
204 }
205 
206 bool SPI::transfer(uint8_t* out_data, uint32_t num_bytes, uint8_t* in_data, GPIO* cs, void (*cb)(void))
207 {
208  busy_ = true;
209 
210  // Save Job parameters
211  in_buffer_ptr_ = (in_data == NULL) ? dummy_buffer : in_data;
212  out_buffer_ptr_ = (out_data == NULL) ? dummy_buffer : out_data;
213  cs_ = cs;
214  transfer_cb_ = cb;
215  num_bytes_ = num_bytes;
216 
218  return true;
219 }
220 
222 {
223  // Configure the DMA
224  DMA_DeInit(c_->Tx_DMA_Stream); // SPI1_TX_DMA_STREAM
225  DMA_DeInit(c_->Rx_DMA_Stream); // SPI1_RX_DMA_STREAM
226 
228 
229  // Configure Tx DMA
231  DMA_InitStructure_.DMA_Memory0BaseAddr = reinterpret_cast<uint32_t>(out_buffer_ptr_);
233 
234  // Configure Rx DMA
236  DMA_InitStructure_.DMA_Memory0BaseAddr = reinterpret_cast<uint32_t>(in_buffer_ptr_);
238 
239  // Configure the Interrupt
241 
242  if (cs_ != NULL)
243  enable(*cs_);
244 
245  // Turn on the DMA streams
248 
249  // Enable the SPI Rx/Tx DMA request
252 }
253 
255 {
256  // uint8_t rxne, txe;
257  // do
258  // {
259  // rxne = SPI_I2S_GetFlagStatus(c_->dev, SPI_I2S_FLAG_RXNE);
260  // txe = SPI_I2S_GetFlagStatus(c_->dev, SPI_I2S_FLAG_TXE);
261  // }while (rxne == RESET || txe == RESET);
262 
263  disable(*cs_);
266 
269 
272 
273  // SPI_Cmd(c_->dev, DISABLE);
274 
275  if (cs_ != NULL)
276  {
277  disable(*cs_);
278  }
279 
280  busy_ = false;
281  if (transfer_cb_ != NULL)
282  transfer_cb_();
283 }
284 
285 extern "C"
286 {
288  {
290  {
292  SPI1ptr->transfer_complete_cb();
293  }
294  }
295 
297  {
299  {
301  SPI2ptr->transfer_complete_cb();
302  }
303  }
304 
306  {
308  {
310  SPI3ptr->transfer_complete_cb();
311  }
312  }
313 }
#define DMA_MemoryInc_Enable
uint32_t DMA_MemoryInc
Definition: stm32f4xx_dma.h:76
void transfer_complete_cb()
Definition: spi.cpp:254
uint16_t SPI_DataSize
Definition: stm32f4xx_spi.h:62
#define DMA_IT_TCIF5
uint32_t DMA_Channel
Definition: stm32f4xx_dma.h:56
void GPIO_PinAFConfig(GPIO_TypeDef *GPIOx, uint16_t GPIO_PinSource, uint8_t GPIO_AF)
Changes the mapping of the specified pin.
#define SPI_NSS_Soft
#define DMA1_Stream5
Definition: stm32f4xx.h:2130
uint32_t num_bytes_
Definition: spi.h:57
void NVIC_Init(NVIC_InitTypeDef *NVIC_InitStruct)
Initializes the NVIC peripheral according to the specified parameters in the NVIC_InitStruct.
uint16_t SPI_Mode
Definition: stm32f4xx_spi.h:59
GPIO sck_
Definition: spi.h:62
#define SPI2
Definition: stm32f4xx.h:2050
uint16_t MISO_Pin
Definition: system.h:66
#define SPI1
Definition: stm32f4xx.h:2087
#define DMA_MemoryDataSize_Byte
#define SPI3
Definition: stm32f4xx.h:2051
#define SPI_Mode_Master
uint16_t SPI_I2S_ReceiveData(SPI_TypeDef *SPIx)
Returns the most recent received data by the SPIx/I2Sx peripheral.
void DMA2_Stream3_IRQHandler()
Definition: spi.cpp:287
Definition: spi.h:37
uint16_t SPI_BaudRatePrescaler
Definition: stm32f4xx_spi.h:75
uint32_t DMA_MemoryBurst
void DMA_DeInit(DMA_Stream_TypeDef *DMAy_Streamx)
Deinitialize the DMAy Streamx registers to their default reset values.
#define DMA_PeripheralInc_Disable
#define DMA_IT_TCIF3
uint16_t SPI_CPOL
Definition: stm32f4xx_spi.h:65
void enable(GPIO &cs)
Definition: spi.cpp:150
const spi_hardware_struct_t * c_
Definition: spi.h:59
bool transfer(uint8_t *out_data, uint32_t num_bytes, uint8_t *in_data, GPIO *cs=NULL, void(*cb)(void)=NULL)
Definition: spi.cpp:206
uint16_t SPI_Direction
Definition: stm32f4xx_spi.h:56
void(* transfer_cb_)(void)
Definition: spi.h:69
uint16_t SCK_Pin
Definition: system.h:62
uint16_t SPI_CRCPolynomial
Definition: stm32f4xx_spi.h:84
void SPI_I2S_DeInit(SPI_TypeDef *SPIx)
Deinitializes the SPIx peripheral registers to their default reset values.
uint32_t DMA_MemoryDataSize
Definition: stm32f4xx_dma.h:82
DMA_Stream_TypeDef * Rx_DMA_Stream
Definition: system.h:70
static uint8_t dummy_buffer[256]
Definition: spi.cpp:38
#define DMA_Priority_High
#define SPI_I2S_DMAReq_Tx
void DMA_Init(DMA_Stream_TypeDef *DMAy_Streamx, DMA_InitTypeDef *DMA_InitStruct)
Initializes the DMAy Streamx according to the specified parameters in the DMA_InitStruct structure...
uint32_t DMA_DIR
Definition: stm32f4xx_dma.h:65
#define SPI_BaudRatePrescaler_32
__IO uint16_t CR1
Definition: stm32f4xx.h:1582
FlagStatus SPI_I2S_GetFlagStatus(SPI_TypeDef *SPIx, uint16_t SPI_I2S_FLAG)
Checks whether the specified SPI flag is set or not.
uint32_t DMA_PeripheralInc
Definition: stm32f4xx_dma.h:73
#define DMA_DIR_MemoryToPeripheral
bool write(const uint8_t *out_data, uint32_t num_bytes, GPIO *cs=NULL)
Definition: spi.cpp:191
ITStatus DMA_GetITStatus(DMA_Stream_TypeDef *DMAy_Streamx, uint32_t DMA_IT)
Checks whether the specified DMAy Streamx interrupt has occurred or not.
#define SPI_BaudRatePrescaler_256
const uint8_t * out_buffer_ptr_
Definition: spi.h:56
void DMA_ClearITPendingBit(DMA_Stream_TypeDef *DMAy_Streamx, uint32_t DMA_IT)
Clears the DMAy Streamx&#39;s interrupt pending bits.
void DMA_ITConfig(DMA_Stream_TypeDef *DMAy_Streamx, uint32_t DMA_IT, FunctionalState NewState)
Enables or disables the specified DMAy Streamx interrupts.
uint32_t DMA_PeripheralDataSize
Definition: stm32f4xx_dma.h:79
#define DMA2_Stream3
Definition: stm32f4xx.h:2137
void SPI_CalculateCRC(SPI_TypeDef *SPIx, FunctionalState NewState)
Enables or disables the CRC value calculation of the transferred bytes.
GPIO * cs_
Definition: spi.h:67
uint32_t DMA_Channel
Definition: system.h:71
#define SPI_BaudRatePrescaler_16
void init(GPIO_TypeDef *BasePort, uint16_t pin, gpio_mode_t mode)
Definition: gpio.cpp:34
uint8_t MOSI_PinSource
Definition: system.h:63
IRQn_Type DMA_IRQn
Definition: system.h:68
#define SPI_I2S_FLAG_TXE
uint8_t SCK_PinSource
Definition: system.h:61
GPIO miso_
Definition: spi.h:61
uint32_t DMA_PeripheralBurst
#define SPI_CPHA_2Edge
void SPI_I2S_DMACmd(SPI_TypeDef *SPIx, uint16_t SPI_I2S_DMAReq, FunctionalState NewState)
Enables or disables the SPIx/I2Sx DMA interface.
#define SPI_BaudRatePrescaler_2
static volatile int16_t temp
Definition: drv_mpu6050.c:278
#define DMA_FIFOThreshold_1QuarterFull
void DMA_Cmd(DMA_Stream_TypeDef *DMAy_Streamx, FunctionalState NewState)
Enables or disables the specified DMAy Streamx.
SPI * SPI1ptr
Definition: spi.cpp:34
uint32_t DMA_PeripheralBaseAddr
Definition: stm32f4xx_dma.h:59
uint16_t MOSI_Pin
Definition: system.h:64
SPI Init structure definition.
Definition: stm32f4xx_spi.h:54
uint16_t SPI_NSS
Definition: stm32f4xx_spi.h:71
SPI_TypeDef * dev
Definition: system.h:59
uint32_t DMA_Memory0BaseAddr
Definition: stm32f4xx_dma.h:61
#define SPI_Direction_2Lines_FullDuplex
uint32_t Rx_DMA_TCIF
Definition: system.h:73
volatile bool busy_
Definition: spi.h:68
#define DMA_MemoryBurst_Single
#define SPI_I2S_FLAG_RXNE
uint32_t DMA_FIFOThreshold
Definition: stm32f4xx_dma.h:98
#define SPI_DataSize_8b
void DMA1_Stream5_IRQHandler()
Definition: spi.cpp:305
void SPI_Cmd(SPI_TypeDef *SPIx, FunctionalState NewState)
Enables or disables the specified SPI peripheral.
GPIO_TypeDef * GPIO
Definition: system.h:60
#define SPI_CPOL_High
void SPI_Init(SPI_TypeDef *SPIx, SPI_InitTypeDef *SPI_InitStruct)
Initializes the SPIx peripheral according to the specified parameters in the SPI_InitStruct.
uint8_t transfer_byte(uint8_t data, GPIO *cs=NULL)
Definition: spi.cpp:160
#define SPI_BaudRatePrescaler_128
#define DMA_Mode_Normal
#define SPI_BaudRatePrescaler_64
void write(gpio_write_t state)
Definition: gpio.cpp:41
#define DMA_FIFOMode_Disable
void DMA1_Stream4_IRQHandler()
Definition: spi.cpp:296
GPIO mosi_
Definition: spi.h:60
void set_divisor(uint16_t new_divisor)
Definition: spi.cpp:109
uint8_t * in_buffer_ptr_
Definition: spi.h:55
uint16_t SPI_FirstBit
Definition: stm32f4xx_spi.h:81
uint32_t DMA_FIFOMode
Definition: stm32f4xx_dma.h:93
#define DMA_PeripheralDataSize_Byte
#define DMA1_Stream4
Definition: stm32f4xx.h:2129
uint16_t SPI_CPHA
Definition: stm32f4xx_spi.h:68
Definition: gpio.h:37
uint32_t Tx_DMA_TCIF
Definition: system.h:72
DMA_InitTypeDef DMA_InitStructure_
Definition: spi.h:64
void cb(uint8_t byte)
Definition: ublox.cpp:8
void perform_transfer()
Definition: spi.cpp:221
#define SPI_FirstBit_MSB
Definition: gpio.h:43
void init(const spi_hardware_struct_t *conf)
Definition: spi.cpp:40
uint32_t DMA_Mode
Definition: stm32f4xx_dma.h:85
#define NULL
Definition: usbd_def.h:50
SPI * SPI3ptr
Definition: spi.cpp:36
#define DMA_DIR_PeripheralToMemory
void SPI_I2S_SendData(SPI_TypeDef *SPIx, uint16_t Data)
Transmits a Data through the SPIx/I2Sx peripheral.
void disable(GPIO &cs)
Definition: spi.cpp:155
SPI * SPI2ptr
Definition: spi.cpp:35
uint32_t DMA_BufferSize
Definition: stm32f4xx_dma.h:69
__IO uint16_t DR
Definition: stm32f4xx.h:1588
uint32_t DMA_Priority
Definition: stm32f4xx_dma.h:90
uint8_t MISO_PinSource
Definition: system.h:65
#define SPI_BaudRatePrescaler_4
#define DMA_IT_TCIF4
void DMA_ClearFlag(DMA_Stream_TypeDef *DMAy_Streamx, uint32_t DMA_FLAG)
Clears the DMAy Streamx&#39;s pending flags.
DMA_Stream_TypeDef * Tx_DMA_Stream
Definition: system.h:69
#define SPI_BaudRatePrescaler_8
#define SPI_I2S_DMAReq_Rx
#define DMA_IT_TC
#define DMA_PeripheralBurst_Single


rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:07:48