Fixes #13934: Fix motor(PWM protocol) spin while fc reset. (#13937)
[betaflight.git] / src / main / io / serial_4way_stk500v2.c
blob3cadd514c30f05f4d103750a5a069360fe5aa303
1 /*
2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
8 * any later version.
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
22 * Author: 4712
23 * have a look at https://github.com/sim-/tgy/blob/master/boot.inc
24 * for info about the stk500v2 implementation
27 #include <stdbool.h>
28 #include <stdint.h>
30 #include "platform.h"
32 #if defined(USE_SERIAL_4WAY_BLHELI_INTERFACE) && defined(USE_SERIAL_4WAY_SK_BOOTLOADER)
34 #include "drivers/io.h"
35 #include "drivers/serial.h"
36 #include "drivers/time.h"
38 #include "io/serial.h"
39 #include "io/serial_4way.h"
40 #include "io/serial_4way_impl.h"
41 #include "io/serial_4way_stk500v2.h"
44 #define BIT_LO_US (32) //32uS
45 #define BIT_HI_US (2*BIT_LO_US)
47 static uint8_t StkInBuf[16];
49 #define STK_BIT_TIMEOUT 250 // micro seconds
50 #define STK_WAIT_TICKS (1000 / STK_BIT_TIMEOUT) // per ms
51 #define STK_WAITCYLCES (STK_WAIT_TICKS * 35) // 35ms
52 #define STK_WAITCYLCES_START (STK_WAIT_TICKS / 2) // 0.5 ms
53 #define STK_WAITCYLCES_EXT (STK_WAIT_TICKS * 5000) //5 s
55 #define WaitPinLo while (ESC_IS_HI) {if (micros() > timeout_timer) goto timeout;}
56 #define WaitPinHi while (ESC_IS_LO) {if (micros() > timeout_timer) goto timeout;}
58 static uint32_t LastBitTime;
59 static uint32_t HiLoTsh;
61 static uint8_t SeqNumber;
62 static uint8_t StkCmd;
63 static uint8_t ckSumIn;
64 static uint8_t ckSumOut;
66 // used STK message constants from ATMEL AVR - Application note
67 #define MESSAGE_START 0x1B
68 #define TOKEN 0x0E
70 #define CMD_SIGN_ON 0x01
71 #define CMD_LOAD_ADDRESS 0x06
72 #define CMD_CHIP_ERASE_ISP 0x12
73 #define CMD_PROGRAM_FLASH_ISP 0x13
74 #define CMD_READ_FLASH_ISP 0x14
75 #define CMD_PROGRAM_EEPROM_ISP 0x15
76 #define CMD_READ_EEPROM_ISP 0x16
77 #define CMD_READ_SIGNATURE_ISP 0x1B
78 #define CMD_SPI_MULTI 0x1D
80 #define STATUS_CMD_OK 0x00
82 #define CmdFlashEepromRead 0xA0
83 #define EnterIspCmd1 0xAC
84 #define EnterIspCmd2 0x53
85 #define signature_r 0x30
87 #define delay_us(x) delayMicroseconds(x)
88 #define IRQ_OFF // dummy
89 #define IRQ_ON // dummy
91 static void StkSendByte(uint8_t dat)
93 ckSumOut ^= dat;
94 for (uint8_t i = 0; i < 8; i++) {
95 if (dat & 0x01) {
96 // 1-bits are encoded as 64.0us high, 72.8us low (135.8us total).
97 ESC_SET_HI;
98 delay_us(BIT_HI_US);
99 ESC_SET_LO;
100 delay_us(BIT_HI_US);
101 } else {
102 // 0-bits are encoded as 27.8us high, 34.5us low, 34.4us high, 37.9 low (134.6us total)
103 ESC_SET_HI;
104 delay_us(BIT_LO_US);
105 ESC_SET_LO;
106 delay_us(BIT_LO_US);
107 ESC_SET_HI;
108 delay_us(BIT_LO_US);
109 ESC_SET_LO;
110 delay_us(BIT_LO_US);
112 dat >>= 1;
116 static void StkSendPacketHeader(void)
118 IRQ_OFF;
119 ESC_OUTPUT;
120 StkSendByte(0xFF);
121 StkSendByte(0xFF);
122 StkSendByte(0x7F);
123 ckSumOut = 0;
124 StkSendByte(MESSAGE_START);
125 StkSendByte(++SeqNumber);
128 static void StkSendPacketFooter(void)
130 StkSendByte(ckSumOut);
131 ESC_SET_HI;
132 delay_us(BIT_LO_US);
133 ESC_INPUT;
134 IRQ_ON;
139 static int8_t ReadBit(void)
141 uint32_t btimer = micros();
142 uint32_t timeout_timer = btimer + STK_BIT_TIMEOUT;
143 WaitPinLo;
144 WaitPinHi;
145 LastBitTime = micros() - btimer;
146 if (LastBitTime <= HiLoTsh) {
147 timeout_timer = timeout_timer + STK_BIT_TIMEOUT;
148 WaitPinLo;
149 WaitPinHi;
150 //lo-bit
151 return 0;
152 } else {
153 return 1;
155 timeout:
156 return -1;
159 static uint8_t ReadByte(uint8_t *bt)
161 *bt = 0;
162 for (uint8_t i = 0; i < 8; i++) {
163 int8_t bit = ReadBit();
164 if (bit == -1) goto timeout;
165 if (bit == 1) {
166 *bt |= (1 << i);
169 ckSumIn ^=*bt;
170 return 1;
171 timeout:
172 return 0;
175 static uint8_t StkReadLeader(void)
178 // Reset learned timing
179 HiLoTsh = BIT_HI_US + BIT_LO_US;
181 // Wait for the first bit
182 uint32_t waitcycl; //250uS each
184 if ((StkCmd == CMD_PROGRAM_EEPROM_ISP) || (StkCmd == CMD_CHIP_ERASE_ISP)) {
185 waitcycl = STK_WAITCYLCES_EXT;
186 } else if (StkCmd == CMD_SIGN_ON) {
187 waitcycl = STK_WAITCYLCES_START;
188 } else {
189 waitcycl= STK_WAITCYLCES;
191 for ( ; waitcycl >0 ; waitcycl--) {
192 //check is not timeout
193 if (ReadBit() >- 1) break;
196 //Skip the first bits
197 if (waitcycl == 0) {
198 goto timeout;
201 for (uint8_t i = 0; i < 10; i++) {
202 if (ReadBit() == -1) goto timeout;
205 // learn timing
206 HiLoTsh = (LastBitTime >> 1) + (LastBitTime >> 2);
208 // Read until we get a 0 bit
209 int8_t bit;
210 do {
211 bit = ReadBit();
212 if (bit == -1) goto timeout;
213 } while (bit > 0);
214 return 1;
215 timeout:
216 return 0;
219 static uint8_t StkRcvPacket(uint8_t *pstring)
221 uint8_t bt = 0;
222 uint8_16_u Len;
224 IRQ_OFF;
225 if (!StkReadLeader()) goto Err;
226 ckSumIn=0;
227 if (!ReadByte(&bt) || (bt != MESSAGE_START)) goto Err;
228 if (!ReadByte(&bt) || (bt != SeqNumber)) goto Err;
229 ReadByte(&Len.bytes[1]);
230 if (Len.bytes[1] > 1) goto Err;
231 ReadByte(&Len.bytes[0]);
232 if (Len.bytes[0] < 1) goto Err;
233 if (!ReadByte(&bt) || (bt != TOKEN)) goto Err;
234 if (!ReadByte(&bt) || (bt != StkCmd)) goto Err;
235 if (!ReadByte(&bt) || (bt != STATUS_CMD_OK)) goto Err;
236 for (uint16_t i = 0; i < (Len.word - 2); i++)
238 if (!ReadByte(pstring)) goto Err;
239 pstring++;
241 ReadByte(&bt);
242 if (ckSumIn != 0) goto Err;
243 IRQ_ON;
244 return 1;
245 Err:
246 IRQ_ON;
247 return 0;
250 static uint8_t _CMD_SPI_MULTI_EX(volatile uint8_t * ResByte,uint8_t Cmd,uint8_t AdrHi,uint8_t AdrLo)
252 StkCmd= CMD_SPI_MULTI;
253 StkSendPacketHeader();
254 StkSendByte(0); // hi byte Msg len
255 StkSendByte(8); // lo byte Msg len
256 StkSendByte(TOKEN);
257 StkSendByte(CMD_SPI_MULTI);
258 StkSendByte(4); // NumTX
259 StkSendByte(4); // NumRX
260 StkSendByte(0); // RxStartAdr
261 StkSendByte(Cmd); // {TxData} Cmd
262 StkSendByte(AdrHi); // {TxData} AdrHi
263 StkSendByte(AdrLo); // {TxData} AdrLoch
264 StkSendByte(0); // {TxData} 0
265 StkSendPacketFooter();
266 if (StkRcvPacket((void *)StkInBuf)) { // NumRX + 3
267 if ((StkInBuf[0] == 0x00) && ((StkInBuf[1] == Cmd)||(StkInBuf[1] == 0x00)/* ignore zero returns */) &&(StkInBuf[2] == 0x00)) {
268 *ResByte = StkInBuf[3];
270 return 1;
272 return 0;
275 static uint8_t _CMD_LOAD_ADDRESS(ioMem_t *pMem)
277 // ignore 0xFFFF
278 // assume address is set before and we read or write the immediately following package
279 if ((pMem->D_FLASH_ADDR_H == 0xFF) && (pMem->D_FLASH_ADDR_L == 0xFF)) return 1;
280 StkCmd = CMD_LOAD_ADDRESS;
281 StkSendPacketHeader();
282 StkSendByte(0); // hi byte Msg len
283 StkSendByte(5); // lo byte Msg len
284 StkSendByte(TOKEN);
285 StkSendByte(CMD_LOAD_ADDRESS);
286 StkSendByte(0);
287 StkSendByte(0);
288 StkSendByte(pMem->D_FLASH_ADDR_H);
289 StkSendByte(pMem->D_FLASH_ADDR_L);
290 StkSendPacketFooter();
291 return (StkRcvPacket((void *)StkInBuf));
294 static uint8_t _CMD_READ_MEM_ISP(ioMem_t *pMem)
296 uint8_t LenHi;
297 if (pMem->D_NUM_BYTES>0) {
298 LenHi=0;
299 } else {
300 LenHi=1;
302 StkSendPacketHeader();
303 StkSendByte(0); // hi byte Msg len
304 StkSendByte(4); // lo byte Msg len
305 StkSendByte(TOKEN);
306 StkSendByte(StkCmd);
307 StkSendByte(LenHi);
308 StkSendByte(pMem->D_NUM_BYTES);
309 StkSendByte(CmdFlashEepromRead);
310 StkSendPacketFooter();
311 return (StkRcvPacket(pMem->D_PTR_I));
314 static uint8_t _CMD_PROGRAM_MEM_ISP(ioMem_t *pMem)
316 uint8_16_u Len;
317 uint8_t LenLo = pMem->D_NUM_BYTES;
318 uint8_t LenHi;
319 if (LenLo) {
320 LenHi = 0;
321 Len.word = LenLo + 10;
322 } else {
323 LenHi = 1;
324 Len.word = 256 + 10;
326 StkSendPacketHeader();
327 StkSendByte(Len.bytes[1]); // high byte Msg len
328 StkSendByte(Len.bytes[0]); // low byte Msg len
329 StkSendByte(TOKEN);
330 StkSendByte(StkCmd);
331 StkSendByte(LenHi);
332 StkSendByte(LenLo);
333 StkSendByte(0); // mode
334 StkSendByte(0); // delay
335 StkSendByte(0); // cmd1
336 StkSendByte(0); // cmd2
337 StkSendByte(0); // cmd3
338 StkSendByte(0); // poll1
339 StkSendByte(0); // poll2
340 do {
341 StkSendByte(*pMem->D_PTR_I);
342 pMem->D_PTR_I++;
343 LenLo--;
344 } while (LenLo);
345 StkSendPacketFooter();
346 return StkRcvPacket((void *)StkInBuf);
349 uint8_t Stk_SignOn(void)
351 StkCmd=CMD_SIGN_ON;
352 StkSendPacketHeader();
353 StkSendByte(0); // hi byte Msg len
354 StkSendByte(1); // lo byte Msg len
355 StkSendByte(TOKEN);
356 StkSendByte(CMD_SIGN_ON);
357 StkSendPacketFooter();
358 return (StkRcvPacket((void *) StkInBuf));
361 uint8_t Stk_ConnectEx(uint8_32_u *pDeviceInfo)
363 if (Stk_SignOn()) {
364 if (_CMD_SPI_MULTI_EX(&pDeviceInfo->bytes[1], signature_r,0,1)) {
365 if (_CMD_SPI_MULTI_EX(&pDeviceInfo->bytes[0], signature_r,0,2)) {
366 return 1;
370 return 0;
373 uint8_t Stk_Chip_Erase(void)
375 StkCmd = CMD_CHIP_ERASE_ISP;
376 StkSendPacketHeader();
377 StkSendByte(0); // high byte Msg len
378 StkSendByte(7); // low byte Msg len
379 StkSendByte(TOKEN);
380 StkSendByte(CMD_CHIP_ERASE_ISP);
381 StkSendByte(20); // ChipErase_eraseDelay atmega8
382 StkSendByte(0); // ChipErase_pollMethod atmega8
383 StkSendByte(0xAC);
384 StkSendByte(0x88);
385 StkSendByte(0x13);
386 StkSendByte(0x76);
387 StkSendPacketFooter();
388 return (StkRcvPacket(StkInBuf));
391 uint8_t Stk_ReadFlash(ioMem_t *pMem)
393 if (_CMD_LOAD_ADDRESS(pMem)) {
394 StkCmd = CMD_READ_FLASH_ISP;
395 return (_CMD_READ_MEM_ISP(pMem));
397 return 0;
401 uint8_t Stk_ReadEEprom(ioMem_t *pMem)
403 if (_CMD_LOAD_ADDRESS(pMem)) {
404 StkCmd = CMD_READ_EEPROM_ISP;
405 return (_CMD_READ_MEM_ISP(pMem));
407 return 0;
410 uint8_t Stk_WriteFlash(ioMem_t *pMem)
412 if (_CMD_LOAD_ADDRESS(pMem)) {
413 StkCmd = CMD_PROGRAM_FLASH_ISP;
414 return (_CMD_PROGRAM_MEM_ISP(pMem));
416 return 0;
419 uint8_t Stk_WriteEEprom(ioMem_t *pMem)
421 if (_CMD_LOAD_ADDRESS(pMem)) {
422 StkCmd = CMD_PROGRAM_EEPROM_ISP;
423 return (_CMD_PROGRAM_MEM_ISP(pMem));
425 return 0;
427 #endif