-
Notifications
You must be signed in to change notification settings - Fork 2
/
J.inc
558 lines (527 loc) · 11.5 KB
/
J.inc
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
;**** **** **** **** ****
;
; BLHeli program for controlling brushless motors in helicopters and multirotors
;
; Copyright 2011, 2012 Steffen Skaug
; This program is distributed under the terms of the GNU General Public License
;
; This file is part of BLHeli.
;
; BLHeli 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 3 of the License, or
; (at your option) any later version.
;
; BLHeli 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 BLHeli. If not, see <http://www.gnu.org/licenses/>.
;
;**** **** **** **** ****
;
; Hardware definition file "J"
; L2 L1 L0 RC CC MB MC MA X X Cc Bc Ac Cp Bp Ap
;
;**** **** **** **** ****
;*********************
; Device SiLabs EFM8BB1x/2x
;*********************
IF MCU_48MHZ == 0
$include (SI_EFM8BB1_Defs.inc)
ELSE
$include (SI_EFM8BB2_Defs.inc)
ENDIF
;**** **** **** **** ****
; Uses internal calibrated oscillator set to 24/48Mhz
;**** **** **** **** ****
;**** **** **** **** ****
; Constant definitions
;**** **** **** **** ****
IF MCU_48MHZ == 0
CSEG AT 1A40h
IF FETON_DELAY == 0
Eep_ESC_Layout: DB "#J_L_00# " ; ESC layout tag
ELSEIF FETON_DELAY == 5
Eep_ESC_Layout: DB "#J_L_05# "
ELSEIF FETON_DELAY == 10
Eep_ESC_Layout: DB "#J_L_10# "
ELSEIF FETON_DELAY == 15
Eep_ESC_Layout: DB "#J_L_15# "
ELSEIF FETON_DELAY == 20
Eep_ESC_Layout: DB "#J_L_20# "
ELSEIF FETON_DELAY == 25
Eep_ESC_Layout: DB "#J_L_25# "
ELSEIF FETON_DELAY == 30
Eep_ESC_Layout: DB "#J_L_30# "
ELSEIF FETON_DELAY == 40
Eep_ESC_Layout: DB "#J_L_40# "
ELSEIF FETON_DELAY == 50
Eep_ESC_Layout: DB "#J_L_50# "
ELSEIF FETON_DELAY == 70
Eep_ESC_Layout: DB "#J_L_70# "
ELSEIF FETON_DELAY == 90
Eep_ESC_Layout: DB "#J_L_90# "
ENDIF
CSEG AT 1A50h
Eep_ESC_MCU: DB "#BLHELI$EFM8B10#" ; Project and MCU tag (16 Bytes)
ELSE
CSEG AT 1A40h
IF FETON_DELAY == 0
Eep_ESC_Layout: DB "#J_H_00# " ; ESC layout tag
ELSEIF FETON_DELAY == 5
Eep_ESC_Layout: DB "#J_H_05# "
ELSEIF FETON_DELAY == 10
Eep_ESC_Layout: DB "#J_H_10# "
ELSEIF FETON_DELAY == 15
Eep_ESC_Layout: DB "#J_H_15# "
ELSEIF FETON_DELAY == 20
Eep_ESC_Layout: DB "#J_H_20# "
ELSEIF FETON_DELAY == 25
Eep_ESC_Layout: DB "#J_H_25# "
ELSEIF FETON_DELAY == 30
Eep_ESC_Layout: DB "#J_H_30# "
ELSEIF FETON_DELAY == 40
Eep_ESC_Layout: DB "#J_H_40# "
ELSEIF FETON_DELAY == 50
Eep_ESC_Layout: DB "#J_H_50# "
ELSEIF FETON_DELAY == 70
Eep_ESC_Layout: DB "#J_H_70# "
ELSEIF FETON_DELAY == 90
Eep_ESC_Layout: DB "#J_H_90# "
ENDIF
CSEG AT 1A50h
Eep_ESC_MCU: DB "#BLHELI$EFM8B21#" ; Project and MCU tag (16 Bytes)
ENDIF
TEMP_LIMIT EQU 49 ; Temperature measurement ADC value for which main motor power is limited at 80degC (low byte, assuming high byte is 1)
TEMP_LIMIT_STEP EQU 9 ; Temperature measurement ADC value increment for another 10degC
;**** **** **** **** ****
; Bootloader definitions
;**** **** **** **** ****
RTX_PORT EQU P0 ; Receive/Transmit port
RTX_MDOUT EQU P0MDOUT ; Set to 1 for PUSHPULL
RTX_MDIN EQU P0MDIN ; Set to 1 for DIGITAL
RTX_SKIP EQU P0SKIP ; Set to 1 for SKIP
RTX_PIN EQU 4 ; RTX pin
SIGNATURE_001 EQU 0E8h ; Device signature
IF MCU_48MHZ == 0
SIGNATURE_002 EQU 0B1h
ELSE
SIGNATURE_002 EQU 0B2h
ENDIF
;*********************
; PORT 0 definitions *
;*********************
LED_2 EQU 7 ;o
LED_1 EQU 6 ;o
LED_0 EQU 5 ;o
Rcp_In EQU 4 ;i
Comp_Com EQU 3 ;i
Mux_B EQU 2 ;i
Mux_C EQU 1 ;i
Mux_A EQU 0 ;i
P0_DIGITAL EQU NOT((1 SHL Mux_A)+(1 SHL Mux_B)+(1 SHL Mux_C)+(1 SHL Comp_Com))
P0_INIT EQU 0FFh
P0_PUSHPULL EQU (1 SHL LED_0)+(1 SHL LED_1)+(1 SHL LED_2)
P0_SKIP EQU 0FFh
Get_Rcp_Capture_Values MACRO
anl TCON, #0EFh ; Disable timer0
mov Temp1, TL0 ; Get timer0 values
mov Temp2, TH0
IF MCU_48MHZ == 1
mov Temp3, Timer0_X
jnb TCON_TF0, ($+4) ; Check if interrupt is pending
inc Temp3 ; If it is pending, then timer has already wrapped
ENDIF
mov TL0, #0 ; Reset timer0
mov TH0, #0
IF MCU_48MHZ == 1
mov Timer0_X, #0
ENDIF
orl TCON, #10h ; Enable timer0 again
IF MCU_48MHZ == 1
mov A, Clock_Set_At_48MHz
jnz Get_Rcp_End
clr C
mov A, Temp1
rlc A
mov Temp1, A
mov A, Temp2
rlc A
mov Temp2, A
mov A, Temp3
rlc A
mov Temp3, A
Get_Rcp_End:
ENDIF
ENDM
Decode_Dshot_2Msb MACRO
movx A, @DPTR
mov Temp6, A
clr C
subb A, Temp5 ; Subtract previous timestamp
clr C
subb A, Temp1
jc t1_int_msb_fail ; Check that bit is longer than minimum
subb A, Temp1 ; Check if bit is zero or one
mov A, Temp4 ; Shift bit into data byte
rlc A
mov Temp4, A
inc DPL ; Next bit
movx A, @DPTR
mov Temp5, A
clr C
subb A, Temp6
clr C
subb A, Temp1
jc t1_int_msb_fail
subb A, Temp1
mov A, Temp4
rlc A
mov Temp4, A
inc DPL
ENDM
Decode_Dshot_2Lsb MACRO
movx A, @DPTR
mov Temp6, A
clr C
subb A, Temp5 ; Subtract previous timestamp
clr C
subb A, Temp1
jc t1_int_lsb_fail ; Check that bit is longer than minimum
subb A, Temp1 ; Check if bit is zero or one
mov A, Temp3 ; Shift bit into data byte
rlc A
mov Temp3, A
inc DPL ; Next bit
movx A, @DPTR
mov Temp5, A
clr C
subb A, Temp6
clr C
subb A, Temp1
jc t1_int_lsb_fail
subb A, Temp1
mov A, Temp3
rlc A
mov Temp3, A
inc DPL
ENDM
Initialize_PCA MACRO
mov PCA0CN0, #40h ; PCA enabled
mov PCA0MD, #08h ; PCA clock is system clock
IF FETON_DELAY == 0
IF MCU_48MHZ == 0
mov PCA0PWM, #82h ; PCA ARSEL set and 10bits pwm
ELSE
mov PCA0PWM, #83h ; PCA ARSEL set and 11bits pwm
ENDIF
mov PCA0CENT, #00h ; Edge aligned pwm
ELSE
IF MCU_48MHZ == 0
mov PCA0PWM, #81h ; PCA ARSEL set and 9bits pwm
ELSE
mov PCA0PWM, #82h ; PCA ARSEL set and 10bits pwm
ENDIF
mov PCA0CENT, #03h ; Center aligned pwm
ENDIF
ENDM
Set_Pwm_Polarity MACRO
mov PCA0POL, #02h ; Damping inverted, pwm noninverted
ENDM
Enable_Power_Pwm_Module MACRO
IF FETON_DELAY == 0
mov PCA0CPM0, #4Ah ; Enable comparator of module, enable match, set pwm mode
ELSE
mov PCA0CPM0, #42h ; Enable comparator of module, set pwm mode
ENDIF
ENDM
Enable_Damp_Pwm_Module MACRO
IF FETON_DELAY == 0
mov PCA0CPM1, #00h ; Disable
ELSE
mov PCA0CPM1, #42h ; Enable comparator of module, set pwm mode
ENDIF
ENDM
Set_Power_Pwm_Regs MACRO
IF FETON_DELAY == 0
mov PCA0CPL0, Power_Pwm_Reg_L
mov PCA0CPH0, Power_Pwm_Reg_H
ELSE
clr C
mov A, Power_Pwm_Reg_H
rrc A
mov Temp1, A
mov A, Power_Pwm_Reg_L
rrc A
mov PCA0CPL0, A
mov PCA0CPH0, Temp1
ENDIF
ENDM
Set_Damp_Pwm_Regs MACRO
IF FETON_DELAY == 0
mov PCA0CPL1, Damp_Pwm_Reg_L
mov PCA0CPH1, Damp_Pwm_Reg_H
ELSE
clr C
mov A, Damp_Pwm_Reg_H
rrc A
mov Temp1, A
mov A, Damp_Pwm_Reg_L
rrc A
mov PCA0CPL1, A
mov PCA0CPH1, Temp1
ENDIF
ENDM
Clear_COVF_Interrupt MACRO
anl PCA0PWM, #0DFh
ENDM
Clear_CCF_Interrupt MACRO
anl PCA0CN0, #0FEh
ENDM
Enable_COVF_Interrupt MACRO
orl PCA0PWM, #40h
ENDM
Enable_CCF_Interrupt MACRO
orl PCA0CPM0,#01h
ENDM
Disable_COVF_Interrupt MACRO
anl PCA0PWM, #0BFh
ENDM
Disable_CCF_Interrupt MACRO
anl PCA0CPM0,#0FEh
ENDM
;*********************
; PORT 1 definitions *
;*********************
; EQU 7 ;i
; EQU 6 ;i
CcomFET EQU 5 ;o
BcomFET EQU 4 ;o
AcomFET EQU 3 ;o
CpwmFET EQU 2 ;o
BpwmFET EQU 1 ;o
ApwmFET EQU 0 ;o
P1_DIGITAL EQU (1 SHL ApwmFET)+(1 SHL BpwmFET)+(1 SHL CpwmFET)+(1 SHL AcomFET)+(1 SHL BcomFET)+(1 SHL CcomFET)
P1_INIT EQU 00h
P1_PUSHPULL EQU (1 SHL ApwmFET)+(1 SHL BpwmFET)+(1 SHL CpwmFET)+(1 SHL AcomFET)+(1 SHL BcomFET)+(1 SHL CcomFET)
P1_SKIP EQU 3Fh
ApwmFET_on MACRO
setb P1.ApwmFET
IF FETON_DELAY == 0
setb P1.AcomFET
ENDIF
ENDM
ApwmFET_off MACRO
IF FETON_DELAY != 0
clr P1.ApwmFET
ELSE
clr P1.AcomFET
ENDIF
ENDM
BpwmFET_on MACRO
setb P1.BpwmFET
IF FETON_DELAY == 0
setb P1.BcomFET
ENDIF
ENDM
BpwmFET_off MACRO
IF FETON_DELAY != 0
clr P1.BpwmFET
ELSE
clr P1.BcomFET
ENDIF
ENDM
CpwmFET_on MACRO
setb P1.CpwmFET
IF FETON_DELAY == 0
setb P1.CcomFET
ENDIF
ENDM
CpwmFET_off MACRO
IF FETON_DELAY != 0
clr P1.CpwmFET
ELSE
clr P1.CcomFET
ENDIF
ENDM
All_pwmFETs_Off MACRO
IF FETON_DELAY != 0
clr P1.ApwmFET
clr P1.BpwmFET
clr P1.CpwmFET
ELSE
clr P1.AcomFET
clr P1.BcomFET
clr P1.CcomFET
ENDIF
ENDM
AcomFET_on MACRO
IF FETON_DELAY == 0
clr P1.ApwmFET
ENDIF
setb P1.AcomFET
ENDM
AcomFET_off MACRO
clr P1.AcomFET
ENDM
BcomFET_on MACRO
IF FETON_DELAY == 0
clr P1.BpwmFET
ENDIF
setb P1.BcomFET
ENDM
BcomFET_off MACRO
clr P1.BcomFET
ENDM
CcomFET_on MACRO
IF FETON_DELAY == 0
clr P1.CpwmFET
ENDIF
setb P1.CcomFET
ENDM
CcomFET_off MACRO
clr P1.CcomFET
ENDM
All_comFETs_Off MACRO
clr P1.AcomFET
clr P1.BcomFET
clr P1.CcomFET
ENDM
Set_Pwm_A MACRO
IF FETON_DELAY == 0
setb P1.AcomFET
mov P1SKIP, #3Eh
ELSE
mov P1SKIP, #36h
ENDIF
ENDM
Set_Pwm_B MACRO
IF FETON_DELAY == 0
setb P1.BcomFET
mov P1SKIP, #3Dh
ELSE
mov P1SKIP, #2Dh
ENDIF
ENDM
Set_Pwm_C MACRO
IF FETON_DELAY == 0
setb P1.CcomFET
mov P1SKIP, #3Bh
ELSE
mov P1SKIP, #1Bh
ENDIF
ENDM
Set_Pwms_Off MACRO
mov P1SKIP, #7Fh
ENDM
Set_Comp_Phase_A MACRO
mov CMP0MX, #03h ; Set comparator multiplexer to phase A
ENDM
Set_Comp_Phase_B MACRO
mov CMP0MX, #23h ; Set comparator multiplexer to phase B
ENDM
Set_Comp_Phase_C MACRO
mov CMP0MX, #13h ; Set comparator multiplexer to phase C
ENDM
Read_Comp_Out MACRO
mov A, CMP0CN0 ; Read comparator output
ENDM
;*********************
; PORT 2 definitions *
;*********************
DebugPin EQU 0 ;o
P2_PUSHPULL EQU (1 SHL DebugPin)
;**********************
; MCU specific macros *
;**********************
Interrupt_Table_Definition MACRO
CSEG AT 0 ; Code segment start
jmp reset
CSEG AT 03h ; Int0 interrupt
jmp int0_int
IF MCU_48MHZ == 1
CSEG AT 0Bh ; Timer0 overflow interrupt
jmp t0_int
ENDIF
CSEG AT 13h ; Int1 interrupt
jmp int1_int
CSEG AT 1Bh ; Timer1 overflow interrupt
jmp t1_int
CSEG AT 2Bh ; Timer2 overflow interrupt
jmp t2_int
CSEG AT 5Bh ; Pca interrupt
jmp pca_int
CSEG AT 73h ; Timer3 overflow/compare interrupt
jmp t3_int
ENDM
Initialize_Xbar MACRO
mov XBR2, #40h ; Xbar enabled
mov XBR1, #02h ; CEX0 and CEX1 routed to pins
ENDM
Initialize_Comparator MACRO
mov CMP0CN0, #80h ; Comparator enabled, no hysteresis
mov CMP0MD, #00h ; Comparator response time 100ns
ENDM
Initialize_Adc MACRO
mov REF0CN, #0Ch ; Set vdd (3.3V) as reference. Enable temp sensor and bias
IF MCU_48MHZ == 0
mov ADC0CF, #59h ; ADC clock 2MHz, PGA gain 1
ELSE
mov ADC0CF, #0B9h ; ADC clock 2MHz, PGA gain 1
ENDIF
mov ADC0MX, #10h ; Select temp sensor input
mov ADC0CN0, #80h ; ADC enabled
mov ADC0CN1, #01h ; Common mode buffer enabled
ENDM
Start_Adc MACRO
mov ADC0CN0, #90h ; ADC start
ENDM
Read_Adc_Result MACRO
mov Temp1, ADC0L
mov Temp2, ADC0H
ENDM
Stop_Adc MACRO
ENDM
Set_RPM_Out MACRO
ENDM
Clear_RPM_Out MACRO
ENDM
Set_MCU_Clk_24MHz MACRO
mov CLKSEL, #13h ; Set clock to 24MHz
mov SFRPAGE, #10h
mov PFE0CN, #00h ; Set flash timing for 24MHz
mov SFRPAGE, #00h
mov Clock_Set_At_48MHz, #0
ENDM
Set_MCU_Clk_48MHz MACRO
mov SFRPAGE, #10h
mov PFE0CN, #30h ; Set flash timing for 48MHz
mov SFRPAGE, #00h
mov CLKSEL, #03h ; Set clock to 48MHz
mov Clock_Set_At_48MHz, #1
ENDM
Set_LED_0 MACRO
clr P0.LED_0
ENDM
Clear_LED_0 MACRO
setb P0.LED_0
ENDM
Set_LED_1 MACRO
clr P0.LED_1
ENDM
Clear_LED_1 MACRO
setb P0.LED_1
ENDM
Set_LED_2 MACRO
clr P0.LED_2
ENDM
Clear_LED_2 MACRO
setb P0.LED_2
ENDM
Set_LED_3 MACRO
ENDM
Clear_LED_3 MACRO
ENDM