Add BST support for TBS CorePro to betaflight
[betaflight.git] / src / main / drivers / bus_bst_stm32f30x.c
blobe2b45e528ddf14a26ba2ff536c5173801ad3d70d
1 /* By Larry Ho Ka Wai @ 23/06/2015*/
3 #include <stdbool.h>
4 #include <stdint.h>
5 #include <stdlib.h>
6 #include <stdarg.h>
7 #include <string.h>
8 #include <math.h>
9 #include <ctype.h>
11 #include <platform.h>
13 #include <build_config.h>
15 #include "bus_bst.h"
18 #ifdef USE_BST
19 #define BST_SHORT_TIMEOUT ((uint32_t)0x1000)
20 #define BST_LONG_TIMEOUT ((uint32_t)(10 * BST_SHORT_TIMEOUT))
22 #if !defined(BST1_SCL_GPIO)
23 #define BST1_SCL_GPIO GPIOB
24 #define BST1_SCL_GPIO_AF GPIO_AF_4
25 #define BST1_SCL_PIN GPIO_Pin_6
26 #define BST1_SCL_PIN_SOURCE GPIO_PinSource6
27 #define BST1_SCL_CLK_SOURCE RCC_AHBPeriph_GPIOB
28 #define BST1_SDA_GPIO GPIOB
29 #define BST1_SDA_GPIO_AF GPIO_AF_4
30 #define BST1_SDA_PIN GPIO_Pin_7
31 #define BST1_SDA_PIN_SOURCE GPIO_PinSource7
32 #define BST1_SDA_CLK_SOURCE RCC_AHBPeriph_GPIOB
33 #endif
35 #if !defined(BST2_SCL_GPIO)
36 #define BST2_SCL_GPIO GPIOF
37 #define BST2_SCL_GPIO_AF GPIO_AF_4
38 #define BST2_SCL_PIN GPIO_Pin_6
39 #define BST2_SCL_PIN_SOURCE GPIO_PinSource6
40 #define BST2_SCL_CLK_SOURCE RCC_AHBPeriph_GPIOF
41 #define BST2_SDA_GPIO GPIOA
42 #define BST2_SDA_GPIO_AF GPIO_AF_4
43 #define BST2_SDA_PIN GPIO_Pin_10
44 #define BST2_SDA_PIN_SOURCE GPIO_PinSource10
45 #define BST2_SDA_CLK_SOURCE RCC_AHBPeriph_GPIOA
46 #endif
48 static uint32_t bstTimeout;
50 static volatile uint16_t bst1ErrorCount = 0;
51 static volatile uint16_t bst2ErrorCount = 0;
53 static I2C_TypeDef *BSTx = NULL;
55 volatile uint8_t CRC8 = 0;
56 volatile bool coreProReady = false;
58 ///////////////////////////////////////////////////////////////////////////////
59 // BST TimeoutUserCallback
60 ///////////////////////////////////////////////////////////////////////////////
62 uint32_t bstTimeoutUserCallback(I2C_TypeDef *BSTx)
64 if (BSTx == I2C1) {
65 bst1ErrorCount++;
66 } else {
67 bst2ErrorCount++;
69 I2C_SoftwareResetCmd(BSTx);
70 return false;
73 void bstInitPort(I2C_TypeDef *BSTx/*, uint8_t Address*/)
75 GPIO_InitTypeDef GPIO_InitStructure;
76 I2C_InitTypeDef BST_InitStructure;
78 if (BSTx == I2C1) {
79 RCC_AHBPeriphClockCmd(BST1_SCL_CLK_SOURCE | BST1_SDA_CLK_SOURCE, ENABLE);
80 RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C1, ENABLE);
81 RCC_I2CCLKConfig(RCC_I2C1CLK_SYSCLK);
83 GPIO_PinAFConfig(BST1_SCL_GPIO, BST1_SCL_PIN_SOURCE, BST1_SCL_GPIO_AF);
84 GPIO_PinAFConfig(BST1_SDA_GPIO, BST1_SDA_PIN_SOURCE, BST1_SDA_GPIO_AF);
86 GPIO_StructInit(&GPIO_InitStructure);
87 I2C_StructInit(&BST_InitStructure);
89 // Init pins
90 GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
91 GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
92 GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
93 GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
95 GPIO_InitStructure.GPIO_Pin = BST1_SCL_PIN;
96 GPIO_Init(BST1_SCL_GPIO, &GPIO_InitStructure);
98 GPIO_InitStructure.GPIO_Pin = BST1_SDA_PIN;
99 GPIO_Init(BST1_SDA_GPIO, &GPIO_InitStructure);
101 I2C_StructInit(&BST_InitStructure);
103 BST_InitStructure.I2C_Mode = I2C_Mode_I2C;
104 BST_InitStructure.I2C_AnalogFilter = I2C_AnalogFilter_Enable;
105 BST_InitStructure.I2C_DigitalFilter = 0x00;
106 BST_InitStructure.I2C_OwnAddress1 = CLEANFLIGHT_FC;
107 //BST_InitStructure.I2C_OwnAddress1 = PNP_PRO_GPS;
108 //BST_InitStructure.I2C_OwnAddress1 = Address;
109 BST_InitStructure.I2C_Ack = I2C_Ack_Enable;
110 BST_InitStructure.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit;
111 BST_InitStructure.I2C_Timing = 0x30E0257A; // 100 Khz, 72Mhz Clock, Analog Filter Delay ON, Rise 100, Fall 10.
113 I2C_Init(I2C1, &BST_InitStructure);
115 I2C_Cmd(I2C1, ENABLE);
118 if (BSTx == I2C2) {
119 RCC_AHBPeriphClockCmd(BST2_SCL_CLK_SOURCE | BST2_SDA_CLK_SOURCE, ENABLE);
120 RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C2, ENABLE);
121 RCC_I2CCLKConfig(RCC_I2C2CLK_SYSCLK);
123 GPIO_PinAFConfig(BST2_SCL_GPIO, BST2_SCL_PIN_SOURCE, BST2_SCL_GPIO_AF);
124 GPIO_PinAFConfig(BST2_SDA_GPIO, BST2_SDA_PIN_SOURCE, BST2_SDA_GPIO_AF);
126 GPIO_StructInit(&GPIO_InitStructure);
127 I2C_StructInit(&BST_InitStructure);
129 // Init pins
130 GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
131 GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
132 GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
133 GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
135 GPIO_InitStructure.GPIO_Pin = BST2_SCL_PIN;
136 GPIO_Init(BST2_SCL_GPIO, &GPIO_InitStructure);
138 GPIO_InitStructure.GPIO_Pin = BST2_SDA_PIN;
139 GPIO_Init(BST2_SDA_GPIO, &GPIO_InitStructure);
141 I2C_StructInit(&BST_InitStructure);
143 BST_InitStructure.I2C_Mode = I2C_Mode_I2C;
144 BST_InitStructure.I2C_AnalogFilter = I2C_AnalogFilter_Enable;
145 BST_InitStructure.I2C_DigitalFilter = 0x00;
146 BST_InitStructure.I2C_OwnAddress1 = CLEANFLIGHT_FC;
147 //BST_InitStructure.I2C_OwnAddress1 = PNP_PRO_GPS;
148 //BST_InitStructure.I2C_OwnAddress1 = Address;
149 BST_InitStructure.I2C_Ack = I2C_Ack_Enable;
150 BST_InitStructure.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit;
151 BST_InitStructure.I2C_Timing = 0x30E0257A; // 100 Khz, 72Mhz Clock, Analog Filter Delay ON, Rise 100, Fall 10.
153 I2C_Init(I2C2, &BST_InitStructure);
155 I2C_Cmd(I2C2, ENABLE);
159 void bstInit(BSTDevice index)
161 if (index == BSTDEV_1) {
162 BSTx = I2C1;
163 } else {
164 BSTx = I2C2;
166 //bstInitPort(BSTx, PNP_PRO_GPS);
167 //bstInitPort(BSTx, CLEANFLIGHT_FC);
168 bstInitPort(BSTx);
171 uint16_t bstGetErrorCounter(void)
173 if (BSTx == I2C1) {
174 return bst1ErrorCount;
177 return bst2ErrorCount;
181 /*************************************************************************************************/
182 uint8_t dataBuffer[64] = {0};
183 uint8_t bufferPointer = 0;
184 uint8_t bstWriteDataLen = 0;
186 bool bstWriteBusy(void)
188 if(bstWriteDataLen)
189 return true;
190 else
191 return false;
194 bool bstMasterWrite(uint8_t* data)
196 if(bstWriteDataLen==0) {
197 CRC8 = 0;
198 bufferPointer = 0;
199 dataBuffer[0] = *data;
200 dataBuffer[1] = *(data+1);
201 bstWriteDataLen = dataBuffer[1] + 2;
202 for(uint8_t i=2; i<bstWriteDataLen; i++) {
203 if(i==(bstWriteDataLen-1)) {
204 crc8Cal(0);
205 dataBuffer[i] = CRC8;
206 } else {
207 dataBuffer[i] = *(data+i);
208 crc8Cal((uint8_t)dataBuffer[i]);
211 return true;
213 return false;
216 bool bstSlaveRead(uint8_t* buf) {
217 if(I2C_GetAddressMatched(BSTx)==CLEANFLIGHT_FC && I2C_GetTransferDirection(BSTx) == I2C_Direction_Transmitter) {
218 //if(I2C_GetTransferDirection(BSTx) == I2C_Direction_Transmitter) {
219 uint8_t len = 0;
220 CRC8 = 0;
221 I2C_ClearFlag(BSTx, I2C_FLAG_ADDR);
223 /* Wait until RXNE flag is set */
224 bstTimeout = BST_LONG_TIMEOUT;
225 while (I2C_GetFlagStatus(BSTx, I2C_ISR_RXNE) == RESET) {
226 if ((bstTimeout--) == 0) {
227 return bstTimeoutUserCallback(BSTx);
230 len = I2C_ReceiveData(BSTx);
231 *buf = len;
232 buf++;
233 while (len) {
234 /* Wait until RXNE flag is set */
235 bstTimeout = BST_LONG_TIMEOUT;
236 while (I2C_GetFlagStatus(BSTx, I2C_ISR_RXNE) == RESET) {
237 if ((bstTimeout--) == 0) {
238 return bstTimeoutUserCallback(BSTx);
241 /* Read data from RXDR */
242 *buf = I2C_ReceiveData(BSTx);
243 if(len == 1)
244 crc8Cal(0);
245 else
246 crc8Cal((uint8_t)*buf);
248 /* Point to the next location where the byte read will be saved */
249 buf++;
251 /* Decrement the read bytes counter */
252 len--;
254 /* If all operations OK */
255 return true;
258 return false;
261 bool bstSlaveWrite(uint8_t* data) {
262 bstTimeout = BST_LONG_TIMEOUT;
263 while (I2C_GetFlagStatus(BSTx, I2C_ISR_ADDR) == RESET) {
264 if ((bstTimeout--) == 0) {
265 return bstTimeoutUserCallback(BSTx);
268 if(I2C_GetAddressMatched(BSTx)==CLEANFLIGHT_FC && I2C_GetTransferDirection(BSTx) == I2C_Direction_Receiver) {
269 //if(I2C_GetTransferDirection(BSTx) == I2C_Direction_Receiver) {
270 uint8_t len = 0;
271 CRC8 = 0;
272 I2C_ClearFlag(BSTx, I2C_FLAG_ADDR);
274 /* Wait until TXIS flag is set */
275 bstTimeout = BST_LONG_TIMEOUT;
276 while (I2C_GetFlagStatus(BSTx, I2C_ISR_TXIS) == RESET) {
277 if ((bstTimeout--) == 0) {
278 return bstTimeoutUserCallback(BSTx);
281 len = *data;
282 data++;
283 I2C_SendData(BSTx, (uint8_t) len);
284 while(len) {
285 /* Wait until TXIS flag is set */
286 bstTimeout = BST_LONG_TIMEOUT;
287 while (I2C_GetFlagStatus(BSTx, I2C_ISR_TXIS) == RESET) {
288 if ((bstTimeout--) == 0) {
289 return bstTimeoutUserCallback(BSTx);
292 if(len == 1) {
293 crc8Cal(0);
294 I2C_SendData(BSTx, (uint8_t) CRC8);
295 } else {
296 crc8Cal((uint8_t)*data);
297 I2C_SendData(BSTx, (uint8_t)*data);
299 /* Point to the next location where the byte read will be saved */
300 data++;
302 /* Decrement the read bytes counter */
303 len--;
305 /* Wait until TXIS flag is set */
306 bstTimeout = BST_LONG_TIMEOUT;
307 while (I2C_GetFlagStatus(BSTx, I2C_ISR_TXIS) == RESET) {
308 if ((bstTimeout--) == 0) {
309 return bstTimeoutUserCallback(BSTx);
312 /* If all operations OK */
313 return true;
315 return false;
318 /*************************************************************************************************/
320 uint32_t bstMasterWriteTimeout = 0;
321 void bstMasterWriteLoop(void)
323 if(bstWriteDataLen != 0) {
324 if(bufferPointer == 0) {
325 bool scl_set = false;
326 if(BSTx == I2C1)
327 scl_set = BST1_SCL_GPIO->IDR&BST1_SCL_PIN;
328 else
329 scl_set = BST2_SCL_GPIO->IDR&BST2_SCL_PIN;
331 if(I2C_GetFlagStatus(BSTx, I2C_ISR_BUSY)==RESET && scl_set) {
332 /* Configure slave address, nbytes, reload, end mode and start or stop generation */
333 I2C_TransferHandling(BSTx, dataBuffer[bufferPointer], 1, I2C_Reload_Mode, I2C_Generate_Start_Write);
334 bstMasterWriteTimeout = micros();
335 bufferPointer++;
337 } else if(bufferPointer == 1) {
338 if(I2C_GetFlagStatus(BSTx, I2C_ISR_TXIS)==SET) {
339 /* Send Register len */
340 I2C_SendData(BSTx, (uint8_t) dataBuffer[bufferPointer]);
341 bstMasterWriteTimeout = micros();
342 } else if(I2C_GetFlagStatus(BSTx, I2C_ISR_TCR)==SET) {
343 /* Configure slave address, nbytes, reload, end mode and start or stop generation */
344 I2C_TransferHandling(BSTx, dataBuffer[bufferPointer-1], dataBuffer[bufferPointer], I2C_AutoEnd_Mode, I2C_No_StartStop);
345 bstMasterWriteTimeout = micros();
346 bufferPointer++;
348 } else if(bufferPointer == bstWriteDataLen) {
349 if(I2C_GetFlagStatus(BSTx, I2C_ISR_STOPF)==SET) {
350 I2C_ClearFlag(BSTx, I2C_ICR_STOPCF);
351 bstWriteDataLen = 0;
352 bufferPointer = 0;
354 } else {
355 if(I2C_GetFlagStatus(BSTx, I2C_ISR_TXIS)==SET) {
356 I2C_SendData(BSTx, (uint8_t) dataBuffer[bufferPointer]);
357 bstMasterWriteTimeout = micros();
358 bufferPointer++;
361 uint32_t currentTime = micros();
362 if(currentTime>bstMasterWriteTimeout+5000) {
363 I2C_SoftwareResetCmd(BSTx);
364 bstWriteDataLen = 0;
365 bufferPointer = 0;
370 void bstMasterReadLoop(void)
373 /*************************************************************************************************/
374 void crc8Cal(uint8_t data_in)
376 /* Polynom = x^8+x^7+x^6+x^4+x^2+1 = x^8+x^7+x^6+x^4+x^2+X^0 */
377 uint8_t Polynom = BST_CRC_POLYNOM;
378 bool MSB_Flag;
380 /* Step through each bit of the BYTE (8-bits) */
381 for (uint8_t i = 0; i < 8; i++) {
382 /* Clear the Flag */
383 MSB_Flag = false;
385 /* MSB_Set = 80; */
386 if (CRC8 & 0x80) {
387 MSB_Flag = true;
390 CRC8 <<= 1;
392 /* MSB_Set = 80; */
393 if (data_in & 0x80) {
394 CRC8++;
396 data_in <<= 1;
398 if (MSB_Flag == true) {
399 CRC8 ^= Polynom;
403 #endif