You can not select more than 25 topics Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.

6938 lines
208 KiB

12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
  1. $NOMOD51
  2. ;**** **** **** **** ****
  3. ;
  4. ; BLHeli program for controlling brushless motors in helicopters and multirotors
  5. ;
  6. ; Copyright 2011, 2012 Steffen Skaug
  7. ; This program is distributed under the terms of the GNU General Public License
  8. ;
  9. ; This file is part of BLHeli.
  10. ;
  11. ; BLHeli is free software: you can redistribute it and/or modify
  12. ; it under the terms of the GNU General Public License as published by
  13. ; the Free Software Foundation, either version 3 of the License, or
  14. ; (at your option) any later version.
  15. ;
  16. ; BLHeli is distributed in the hope that it will be useful,
  17. ; but WITHOUT ANY WARRANTY; without even the implied warranty of
  18. ; MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  19. ; GNU General Public License for more details.
  20. ;
  21. ; You should have received a copy of the GNU General Public License
  22. ; along with BLHeli. If not, see <http://www.gnu.org/licenses/>.
  23. ;
  24. ;**** **** **** **** ****
  25. ;
  26. ; The software was initially designed for use with Eflite mCP X, but is now adapted to copters/planes in general
  27. ;
  28. ; The software was inspired by and started from from Bernard Konze's BLMC: http://home.versanet.de/~bkonze/blc_6a/blc_6a.htm
  29. ; And also Simon Kirby's TGY: https://github.com/sim-/tgy
  30. ;
  31. ; This file is best viewed with tab width set to 5
  32. ;
  33. ; The input signal can be positive 1kHz, 2kHz, 4kHz, 8kHz or 12kHz PWM (e.g. taken from the "resistor tap" on mCPx)
  34. ; And the input signal can be PPM (1-2ms) or OneShot125 (125-250us) at rates up to several hundred Hz.
  35. ; The code adapts itself to the various input modes/frequencies
  36. ; The code ESC can also be programmed to accept inverted input signal.
  37. ;
  38. ; The first lines of the software must be modified according to the chosen environment:
  39. ; Uncomment the selected ESC and main/tail/multi mode
  40. ; BESCNO EQU "ESC"_"mode"
  41. ;
  42. ;**** **** **** **** ****
  43. ; Revision history:
  44. ; - Rev1.0: Initial revision based upon BLHeli for AVR controllers
  45. ; - Rev2.0: Changed "Eeprom" initialization, layout and defaults
  46. ; Various changes and improvements to comparator reading. Now using timer1 for time from pwm on/off
  47. ; Beeps are made louder
  48. ; Added programmable low voltage limit
  49. ; Added programmable damped tail mode (only for 1S ESCs)
  50. ; Added programmable motor rotation direction
  51. ; - Rev2.1: (minor changes by 4712)
  52. ; Added Disable TX Programming by PC Setup Application
  53. ; therfore changed EEPROM_LAYOUT_REVISION = 8
  54. ; Added Vdd Monitor as reset source when writing to "EEProm"
  55. ; Changed for use of batch file to assemble, link and make hex files
  56. ; - Rev2.2: (minor changes by 4712)
  57. ; Added Disable Throttle Re-Arming every motor start by PC Setup Application
  58. ; - Rev2.3: (minor changes by 4712)
  59. ; Added bugfixed (2x CLR C before j(n)c operations)thx Steffen!
  60. ; - Rev2.4: Revisions 2.1 to 2.3 integrated
  61. ; - Rev3.0: Added PPM (1050us-1866us) as accepted input signal
  62. ; Added startup rpm as a programming parameter
  63. ; Added startup acceleration as a programming parameter
  64. ; Added option for using voltage measurements to compensate motor power
  65. ; Added governor target by setup as a governor mode option
  66. ; Governor is kept active regardless of rpm
  67. ; Smooth governor spoolup/down in arm and setup modes
  68. ; Increased governor P and I gain programming ranges
  69. ; Increased and changed low voltage limit programming range
  70. ; Disabled tx programming entry for all but the first arming sequence after power on
  71. ; Made it possible to skip parameters in tx programming by setting throttle midstick
  72. ; Made it default not to rearm for every restart
  73. ; - Rev3.1: Fixed bug that prevented chosen parameter to be set in tx programming
  74. ; - Rev3.2: ...also updated the EEPROM revision parameter
  75. ; - Rev3.3: Fixed negative number bug in voltage compensation
  76. ; Fixed bug in startup power calculation for non-default power
  77. ; Prevented possibility for voltage compensation fighting low voltage limiting
  78. ; Applied overall spoolup control to ensure soft spoolup in any mode
  79. ; Added a delay of 3 seconds from initiation of main motor stop until new startup is allowed
  80. ; Reduced beep power to reduce power consumption for very strong motors/ESCs
  81. ; - Rev3.4: Fixed bug that prevented full power in governor arm and setup modes
  82. ; Increased NFETON_DELAY for XP_7A and XP_12A to allow for more powerful fets
  83. ; Increased initial spoolup power, and linked to startup power
  84. ; - Rev4.0: Fixed bug that made tail tx program beeps very weak
  85. ; Added thermal protection feature
  86. ; Governor P and I gain ranges are extended up to 8.0x gain
  87. ; Startup sequence is aborted upon zero throttle
  88. ; Avoided voltage compensation function induced latency for tail when voltage compensation is not enabled
  89. ; Improved input signal frequency detection robustness
  90. ; - Rev4.1: Increased thermal protection temperature limits
  91. ; - Rev5.0: Added multi(copter) operating mode. TAIL define changed to MODE with three modes: MAIN, TAIL and MULTI
  92. ; Added programmable commutation timing
  93. ; Added a damped light mode that has less damping, but that can be used with all escs
  94. ; Added programmable damping force
  95. ; Added thermal protection for startup too
  96. ; Added wait beeps when waiting more than 30 sec for throttle above zero (after having been armed)
  97. ; Modified tail idling to provide option for very low speeds
  98. ; Changed PPM range to 1150-1830us
  99. ; Arming sequence is dropped for PPM input, unless it is governor arm mode
  100. ; Loss of input signal will immediately stop the motor for PPM input
  101. ; Bug corrected in Turnigy Plush 6A voltage measurement setup
  102. ; FET switching delays are set for original fets. Stronger/doubled/tripled etc fets may require faster pfet off switching
  103. ; Miscellaneous other changes
  104. ; - Rev6.0: Reverted comparator reading routine to rev5.0 equivalent, in order to avoid tail motor stops
  105. ; Added governor range programmability
  106. ; Implemented startup retry sequence with varying startup power for multi mode
  107. ; In damped light mode, damping is now applied to the active nfet phase for fully damped capable ESCs
  108. ; - Rev6.1: Added input signal qualification criteria for PPM, to avoid triggering on noise spikes (fix for plush hardware)
  109. ; Changed main and multi mode stop criteria. Will now be in run mode, even if RC pulse input is zero
  110. ; Fixed bug in commutation that caused rough running in damped light mode
  111. ; Miscellaneous other changes
  112. ; - Rev7.0 Added direct startup mode programmability
  113. ; Added throttle calibration. Min>=1000us and Max<=2000us. Difference must be >520us, otherwise max is shifted so that difference=520us
  114. ; Added programmable throttle change rate
  115. ; Added programmable beep strength, beacon strength and beacon delay
  116. ; Reduced power step to full power significantly
  117. ; Miscellaneous other changes
  118. ; - Rev8.0 Added a 2 second delay after power up, to wait for receiver initialization
  119. ; Added a programming option for disabling low voltage limit, and made it default for MULTI
  120. ; Added programable demag compensation, using the concept of SimonK
  121. ; Improved robustness against noisy input signal
  122. ; Refined direct startup
  123. ; Removed voltage compensation
  124. ; Miscellaneous other changes
  125. ; - Rev9.0 Increased programming range for startup power, and made its default ESC dependent
  126. ; Made default startup method ESC dependent
  127. ; Even more smooth and gentle spoolup for MAIN, to suit larger helis
  128. ; Improved transition from stepped startup to run
  129. ; Refined direct startup
  130. ; - Rev9.1 Fixed bug that changed FW revision after throttle calibration or TX programming
  131. ; - Rev9.2 Altered timing of throttle calibration in order to work with MultiWii calibration firmware
  132. ; Reduced main spoolup time to around 5 seconds
  133. ; Changed default beacon delay to 3 minutes
  134. ; - Rev9.3 Fixed bug in Plush 60/80A temperature reading, that caused failure in operation above 4S
  135. ; Corrected temperature limit for HiModel cool 22/33/41A, RCTimer 6A, Skywalker 20/40A, Turnigy AE45A, Plush 40/60/80A. Limit was previously set too high
  136. ; - Rev9.4 Improved timing for increased maximum rpm limit
  137. ; - Rev10.0 Added closed loop mode for multi
  138. ; Added high/low BEC voltage option (for the ESCs where HW supports it)
  139. ; Added method of resetting all programmed parameter values to defaults by TX programming
  140. ; Added Turnigy K-force 40A and Turnigy K-force 120A HV ESCs
  141. ; Enabled fully damped mode for several ESCs
  142. ; Extended startup power range downwards to enable very smooth start for large heli main motors
  143. ; Extended damping force with a highest setting
  144. ; Corrected temperature limits for F310 chips (Plush 40A and AE 45A)
  145. ; Implemented temperature reading average in order to avoid problems with ADC noise on Skywalkers
  146. ; Increased switching delays for XP 7A fast, in order to avoid cross conduction of N and P fets
  147. ; Miscellaneous other changes
  148. ; - Rev10.1 Relaxed RC signal jitter requirement during frequency measurement
  149. ; Corrected bug that prevented using governor low
  150. ; Enabled vdd monitor always, in order to reduce likelihood of accidental overwriting of adjustments
  151. ; Fixed bug that caused stop for PPM input above 2048us, and moved upper accepted limit to 2160us
  152. ; - Rev10.2 Corrected temperature limit for AE20-30/XP7-25, where limit was too high
  153. ; Corrected temperature limit for 120HV, where limit was too low
  154. ; Fixed bug that caused AE20/25/30A not to run in reverse
  155. ; - Rev10.3 Removed vdd monitor for 1S capable ESCs, in order to avoid brownouts/resets
  156. ; Made auto bailout spoolup for main more smooth
  157. ; - Rev10.4 Ensured that main spoolup and governor activation will always be smooth, regardless of throttle input
  158. ; Added capability to operate on 12kHz input signal too
  159. ; - Rev11.0 Fixed bug of programming default values for governor in MULTI mode
  160. ; Disabled interrupts explicitly some places, to avoid possibilities for unintentional fet switching
  161. ; Changed interrupt disable strategy, to always allow pwm interrupts, to avoid noise when running at low rpms
  162. ; Added governor middle range for MAIN mode
  163. ; Added bidirectional mode for TAIL and MULTI mode with PPM input
  164. ; Changed and improved demag compensation
  165. ; Miscellaneous other changes
  166. ; - Rev11.1 Fixed bug of slow acceleration response for MAIN mode running without governor
  167. ; Fixed bug with PWM input, where throttle remains high even when zeroing throttle (seen on V922 tail)
  168. ; Fixed bug in bidirectional operation, where direction change could cause reset
  169. ; Improved autorotation bailout for MAIN
  170. ; Reduced min speed back to 1220 erpm
  171. ; Misc code cleanups
  172. ; - Rev11.2 Fixed throttle calibration bug
  173. ; Added high side driver precharge for all-nfet ESCs
  174. ; Optimized timing in general and for demag compensation in particular
  175. ; Auto bailout functionality modified
  176. ; Governor is deactivated for throttle inputs below 10%
  177. ; Increased beacon delay times
  178. ; - Rev12.0 Added programmable main spoolup time
  179. ; Added programmable temperature protection enable
  180. ; Bidirectional mode stop/start improved. Motor is now stopped before starting
  181. ; Power is limited for very low rpms (when BEMF is low), in order to avoid sync loss
  182. ; Damped light mode is made more smooth and quiet, particularly at low and high rpms
  183. ; Comparator signal qualification scheme is changed
  184. ; Demag compensation scheme is significantly changed
  185. ; Increased jitter tolerance for PPM frequency measurement
  186. ; Fully damped mode removed, and damped light only supported on damped capable ESCs
  187. ; Default tail mode changed to damped light
  188. ; Miscellaneous other changes
  189. ; - Rev12.1 Fixed bug in tail code
  190. ; Improved startup for Atmel
  191. ; Added support for multiple high BEC voltages
  192. ; Added support for RPM output
  193. ; - Rev12.2 Improved running smoothness, particularly for damped light
  194. ; Avoiding lockup at full throttle when input signal is noisy
  195. ; Avoiding detection of 1-wire programming signal as valid throttle signal
  196. ; - Rev13.0 Removed stepped start
  197. ; Removed throttle change rate and damping force parameters
  198. ; Added support for OneShot125
  199. ; Improved commutation timing accuracy
  200. ; - Rev13.1 Removed startup ramp for MULTI
  201. ; Improved startup for some odd ESCs
  202. ; - Rev13.2 Still tweaking startup to make it more reliable and faster for all ESC/motor combos
  203. ; Increased deadband for bidirectional operation
  204. ; Relaxed signal detection criteria
  205. ; Added support for running 50MHz capable SiLabs MCUs at 50MHz
  206. ; Added bootlader to SiLabs code
  207. ; Miscellaneous other changes
  208. ;
  209. ;
  210. ;
  211. ;**** **** **** **** ****
  212. ; Up to 8K Bytes of In-System Self-Programmable Flash
  213. ; 768 Bytes Internal SRAM
  214. ;
  215. ;**** **** **** **** ****
  216. ; Master clock is internal 24MHz oscillator
  217. ; Timer 0 (167/500ns counts) always counts up and is used for
  218. ; - PWM generation
  219. ; Timer 1 (167/500ns counts) always counts up and is used for
  220. ; - Time from pwm on/off event
  221. ; Timer 2 (500ns counts) always counts up and is used for
  222. ; - RC pulse timeout/skip counts and commutation times
  223. ; Timer 3 (500ns counts) always counts up and is used for
  224. ; - Commutation timeouts
  225. ; PCA0 (500ns counts) always counts up and is used for
  226. ; - RC pulse measurement
  227. ;
  228. ;**** **** **** **** ****
  229. ; Interrupt handling
  230. ; The F330/2 does not disable interrupts when entering an interrupt routine.
  231. ; Also some interrupt flags need to be cleared by software
  232. ; The code disables interrupts in interrupt routines, in order to avoid too nested interrupts
  233. ; - Interrupts are disabled during beeps, to avoid audible interference from interrupts
  234. ; - RC pulse interrupts are periodically disabled in order to reduce interference with pwm interrupts.
  235. ;
  236. ;**** **** **** **** ****
  237. ; Motor control:
  238. ; - Brushless motor control with 6 states for each electrical 360 degrees
  239. ; - An advance timing of 0deg has zero cross 30deg after one commutation and 30deg before the next
  240. ; - Timing advance in this implementation is set to 15deg nominally
  241. ; - "Damped" commutation schemes are available, where more than one pfet is on when pwm is off. This will absorb energy from bemf and make step settling more damped.
  242. ; Motor sequence starting from zero crossing:
  243. ; - Timer wait: Wt_Comm 15deg ; Time to wait from zero cross to actual commutation
  244. ; - Timer wait: Wt_Advance 15deg ; Time to wait for timing advance. Nominal commutation point is after this
  245. ; - Timer wait: Wt_Zc_Scan 7.5deg ; Time to wait before looking for zero cross
  246. ; - Scan for zero cross 22.5deg , Nominal, with some motor variations
  247. ;
  248. ; Motor startup:
  249. ; Startup is the only phase, before normal bemf commutation run begins.
  250. ;
  251. ;**** **** **** **** ****
  252. ; List of enumerated supported ESCs and modes (main, tail or multi)
  253. XP_3A_Main EQU 1
  254. XP_3A_Tail EQU 2
  255. XP_3A_Multi EQU 3
  256. XP_7A_Main EQU 4
  257. XP_7A_Tail EQU 5
  258. XP_7A_Multi EQU 6
  259. XP_7A_Fast_Main EQU 7
  260. XP_7A_Fast_Tail EQU 8
  261. XP_7A_Fast_Multi EQU 9
  262. XP_12A_Main EQU 10
  263. XP_12A_Tail EQU 11
  264. XP_12A_Multi EQU 12
  265. XP_18A_Main EQU 13
  266. XP_18A_Tail EQU 14
  267. XP_18A_Multi EQU 15
  268. XP_25A_Main EQU 16
  269. XP_25A_Tail EQU 17
  270. XP_25A_Multi EQU 18
  271. XP_35A_SW_Main EQU 19
  272. XP_35A_SW_Tail EQU 20
  273. XP_35A_SW_Multi EQU 21
  274. DP_3A_Main EQU 22
  275. DP_3A_Tail EQU 23
  276. DP_3A_Multi EQU 24
  277. Supermicro_3p5A_Main EQU 25
  278. Supermicro_3p5A_Tail EQU 26
  279. Supermicro_3p5A_Multi EQU 27
  280. Turnigy_Plush_6A_Main EQU 28
  281. Turnigy_Plush_6A_Tail EQU 29
  282. Turnigy_Plush_6A_Multi EQU 30
  283. Turnigy_Plush_10A_Main EQU 31
  284. Turnigy_Plush_10A_Tail EQU 32
  285. Turnigy_Plush_10A_Multi EQU 33
  286. Turnigy_Plush_12A_Main EQU 34
  287. Turnigy_Plush_12A_Tail EQU 35
  288. Turnigy_Plush_12A_Multi EQU 36
  289. Turnigy_Plush_18A_Main EQU 37
  290. Turnigy_Plush_18A_Tail EQU 38
  291. Turnigy_Plush_18A_Multi EQU 39
  292. Turnigy_Plush_25A_Main EQU 40
  293. Turnigy_Plush_25A_Tail EQU 41
  294. Turnigy_Plush_25A_Multi EQU 42
  295. Turnigy_Plush_30A_Main EQU 43
  296. Turnigy_Plush_30A_Tail EQU 44
  297. Turnigy_Plush_30A_Multi EQU 45
  298. Turnigy_Plush_40A_Main EQU 46
  299. Turnigy_Plush_40A_Tail EQU 47
  300. Turnigy_Plush_40A_Multi EQU 48
  301. Turnigy_Plush_60A_Main EQU 49
  302. Turnigy_Plush_60A_Tail EQU 50
  303. Turnigy_Plush_60A_Multi EQU 51
  304. Turnigy_Plush_80A_Main EQU 52
  305. Turnigy_Plush_80A_Tail EQU 53
  306. Turnigy_Plush_80A_Multi EQU 54
  307. Turnigy_Plush_Nfet_18A_Main EQU 55
  308. Turnigy_Plush_Nfet_18A_Tail EQU 56
  309. Turnigy_Plush_Nfet_18A_Multi EQU 57
  310. Turnigy_Plush_Nfet_25A_Main EQU 58
  311. Turnigy_Plush_Nfet_25A_Tail EQU 59
  312. Turnigy_Plush_Nfet_25A_Multi EQU 60
  313. Turnigy_Plush_Nfet_30A_Main EQU 61
  314. Turnigy_Plush_Nfet_30A_Tail EQU 62
  315. Turnigy_Plush_Nfet_30A_Multi EQU 63
  316. Turnigy_AE_20A_Main EQU 64
  317. Turnigy_AE_20A_Tail EQU 65
  318. Turnigy_AE_20A_Multi EQU 66
  319. Turnigy_AE_25A_Main EQU 67
  320. Turnigy_AE_25A_Tail EQU 68
  321. Turnigy_AE_25A_Multi EQU 69
  322. Turnigy_AE_30A_Main EQU 70
  323. Turnigy_AE_30A_Tail EQU 71
  324. Turnigy_AE_30A_Multi EQU 72
  325. Turnigy_AE_45A_Main EQU 73
  326. Turnigy_AE_45A_Tail EQU 74
  327. Turnigy_AE_45A_Multi EQU 75
  328. Turnigy_KForce_40A_Main EQU 76
  329. Turnigy_KForce_40A_Tail EQU 77
  330. Turnigy_KForce_40A_Multi EQU 78
  331. Turnigy_KForce_70A_HV_Main EQU 79
  332. Turnigy_KForce_70A_HV_Tail EQU 80
  333. Turnigy_KForce_70A_HV_Multi EQU 81
  334. Turnigy_KForce_120A_HV_Main EQU 82
  335. Turnigy_KForce_120A_HV_Tail EQU 83
  336. Turnigy_KForce_120A_HV_Multi EQU 84
  337. Turnigy_KForce_120A_HV_v2_Main EQU 85
  338. Turnigy_KForce_120A_HV_v2_Tail EQU 86
  339. Turnigy_KForce_120A_HV_v2_Multi EQU 87
  340. Skywalker_20A_Main EQU 88
  341. Skywalker_20A_Tail EQU 89
  342. Skywalker_20A_Multi EQU 90
  343. Skywalker_40A_Main EQU 91
  344. Skywalker_40A_Tail EQU 92
  345. Skywalker_40A_Multi EQU 93
  346. HiModel_Cool_22A_Main EQU 94
  347. HiModel_Cool_22A_Tail EQU 95
  348. HiModel_Cool_22A_Multi EQU 96
  349. HiModel_Cool_33A_Main EQU 97
  350. HiModel_Cool_33A_Tail EQU 98
  351. HiModel_Cool_33A_Multi EQU 99
  352. HiModel_Cool_41A_Main EQU 100
  353. HiModel_Cool_41A_Tail EQU 101
  354. HiModel_Cool_41A_Multi EQU 102
  355. RCTimer_6A_Main EQU 103
  356. RCTimer_6A_Tail EQU 104
  357. RCTimer_6A_Multi EQU 105
  358. Align_RCE_BL15X_Main EQU 106
  359. Align_RCE_BL15X_Tail EQU 107
  360. Align_RCE_BL15X_Multi EQU 108
  361. Align_RCE_BL15P_Main EQU 109
  362. Align_RCE_BL15P_Tail EQU 110
  363. Align_RCE_BL15P_Multi EQU 111
  364. Align_RCE_BL35X_Main EQU 112
  365. Align_RCE_BL35X_Tail EQU 113
  366. Align_RCE_BL35X_Multi EQU 114
  367. Align_RCE_BL35P_Main EQU 115
  368. Align_RCE_BL35P_Tail EQU 116
  369. Align_RCE_BL35P_Multi EQU 117
  370. Gaui_GE_183_18A_Main EQU 118
  371. Gaui_GE_183_18A_Tail EQU 119
  372. Gaui_GE_183_18A_Multi EQU 120
  373. H_King_10A_Main EQU 121
  374. H_King_10A_Tail EQU 122
  375. H_King_10A_Multi EQU 123
  376. H_King_20A_Main EQU 124
  377. H_King_20A_Tail EQU 125
  378. H_King_20A_Multi EQU 126
  379. H_King_35A_Main EQU 127
  380. H_King_35A_Tail EQU 128
  381. H_King_35A_Multi EQU 129
  382. H_King_50A_Main EQU 130
  383. H_King_50A_Tail EQU 131
  384. H_King_50A_Multi EQU 132
  385. Polaris_Thunder_12A_Main EQU 133
  386. Polaris_Thunder_12A_Tail EQU 134
  387. Polaris_Thunder_12A_Multi EQU 135
  388. Polaris_Thunder_20A_Main EQU 136
  389. Polaris_Thunder_20A_Tail EQU 137
  390. Polaris_Thunder_20A_Multi EQU 138
  391. Polaris_Thunder_30A_Main EQU 139
  392. Polaris_Thunder_30A_Tail EQU 140
  393. Polaris_Thunder_30A_Multi EQU 141
  394. Polaris_Thunder_40A_Main EQU 142
  395. Polaris_Thunder_40A_Tail EQU 143
  396. Polaris_Thunder_40A_Multi EQU 144
  397. Polaris_Thunder_60A_Main EQU 145
  398. Polaris_Thunder_60A_Tail EQU 146
  399. Polaris_Thunder_60A_Multi EQU 147
  400. Polaris_Thunder_80A_Main EQU 148
  401. Polaris_Thunder_80A_Tail EQU 149
  402. Polaris_Thunder_80A_Multi EQU 150
  403. Polaris_Thunder_100A_Main EQU 151
  404. Polaris_Thunder_100A_Tail EQU 152
  405. Polaris_Thunder_100A_Multi EQU 153
  406. Platinum_Pro_30A_Main EQU 154
  407. Platinum_Pro_30A_Tail EQU 155
  408. Platinum_Pro_30A_Multi EQU 156
  409. Platinum_Pro_150A_Main EQU 157
  410. Platinum_Pro_150A_Tail EQU 158
  411. Platinum_Pro_150A_Multi EQU 159
  412. Platinum_50Av3_Main EQU 160
  413. Platinum_50Av3_Tail EQU 161
  414. Platinum_50Av3_Multi EQU 162
  415. EAZY_3Av2_Main EQU 163
  416. EAZY_3Av2_Tail EQU 164
  417. EAZY_3Av2_Multi EQU 165
  418. Tarot_30A_Main EQU 166
  419. Tarot_30A_Tail EQU 167
  420. Tarot_30A_Multi EQU 168
  421. SkyIII_30A_Main EQU 169
  422. SkyIII_30A_Tail EQU 170
  423. SkyIII_30A_Multi EQU 171
  424. EMAX_20A_Main EQU 172
  425. EMAX_20A_Tail EQU 173
  426. EMAX_20A_Multi EQU 174
  427. EMAX_40A_Main EQU 175
  428. EMAX_40A_Tail EQU 176
  429. EMAX_40A_Multi EQU 177
  430. XRotor_10A_Main EQU 178
  431. XRotor_10A_Tail EQU 179
  432. XRotor_10A_Multi EQU 180
  433. XRotor_20A_Main EQU 181
  434. XRotor_20A_Tail EQU 182
  435. XRotor_20A_Multi EQU 183
  436. XRotor_40A_Main EQU 184
  437. XRotor_40A_Tail EQU 185
  438. XRotor_40A_Multi EQU 186
  439. ;**** **** **** **** ****
  440. ; Select the ESC and mode to use (or unselect all for use with external batch compile file)
  441. ;BESCNO EQU XP_3A_Main
  442. ;BESCNO EQU XP_3A_Tail
  443. ;BESCNO EQU XP_3A_Multi
  444. ;BESCNO EQU XP_7A_Main
  445. ;BESCNO EQU XP_7A_Tail
  446. ;BESCNO EQU XP_7A_Multi
  447. ;BESCNO EQU XP_7A_Fast_Main
  448. ;BESCNO EQU XP_7A_Fast_Tail
  449. ;BESCNO EQU XP_7A_Fast_Multi
  450. ;BESCNO EQU XP_12A_Main
  451. ;BESCNO EQU XP_12A_Tail
  452. ;BESCNO EQU XP_12A_Multi
  453. ;BESCNO EQU XP_18A_Main
  454. ;BESCNO EQU XP_18A_Tail
  455. ;BESCNO EQU XP_18A_Multi
  456. ;BESCNO EQU XP_25A_Main
  457. ;BESCNO EQU XP_25A_Tail
  458. ;BESCNO EQU XP_25A_Multi
  459. ;BESCNO EQU XP_35A_SW_Main
  460. ;BESCNO EQU XP_35A_SW_Tail
  461. ;BESCNO EQU XP_35A_SW_Multi
  462. ;BESCNO EQU DP_3A_Main
  463. ;BESCNO EQU DP_3A_Tail
  464. ;BESCNO EQU DP_3A_Multi
  465. ;BESCNO EQU Supermicro_3p5A_Main
  466. ;BESCNO EQU Supermicro_3p5A_Tail
  467. ;BESCNO EQU Supermicro_3p5A_Multi
  468. ;BESCNO EQU Turnigy_Plush_6A_Main
  469. ;BESCNO EQU Turnigy_Plush_6A_Tail
  470. ;BESCNO EQU Turnigy_Plush_6A_Multi
  471. ;BESCNO EQU Turnigy_Plush_10A_Main
  472. ;BESCNO EQU Turnigy_Plush_10A_Tail
  473. ;BESCNO EQU Turnigy_Plush_10A_Multi
  474. ;BESCNO EQU Turnigy_Plush_12A_Main
  475. ;BESCNO EQU Turnigy_Plush_12A_Tail
  476. ;BESCNO EQU Turnigy_Plush_12A_Multi
  477. ;BESCNO EQU Turnigy_Plush_18A_Main
  478. ;BESCNO EQU Turnigy_Plush_18A_Tail
  479. ;BESCNO EQU Turnigy_Plush_18A_Multi
  480. ;BESCNO EQU Turnigy_Plush_25A_Main
  481. ;BESCNO EQU Turnigy_Plush_25A_Tail
  482. ;BESCNO EQU Turnigy_Plush_25A_Multi
  483. ;BESCNO EQU Turnigy_Plush_30A_Main
  484. ;BESCNO EQU Turnigy_Plush_30A_Tail
  485. ;BESCNO EQU Turnigy_Plush_30A_Multi
  486. ;BESCNO EQU Turnigy_Plush_40A_Main
  487. ;BESCNO EQU Turnigy_Plush_40A_Tail
  488. ;BESCNO EQU Turnigy_Plush_40A_Multi
  489. ;BESCNO EQU Turnigy_Plush_60A_Main
  490. ;BESCNO EQU Turnigy_Plush_60A_Tail
  491. ;BESCNO EQU Turnigy_Plush_60A_Multi
  492. ;BESCNO EQU Turnigy_Plush_80A_Main
  493. ;BESCNO EQU Turnigy_Plush_80A_Tail
  494. ;BESCNO EQU Turnigy_Plush_80A_Multi
  495. ;BESCNO EQU Turnigy_Plush_Nfet_18A_Main
  496. ;BESCNO EQU Turnigy_Plush_Nfet_18A_Tail
  497. ;BESCNO EQU Turnigy_Plush_Nfet_18A_Multi
  498. ;BESCNO EQU Turnigy_Plush_Nfet_25A_Main
  499. ;BESCNO EQU Turnigy_Plush_Nfet_25A_Tail
  500. ;BESCNO EQU Turnigy_Plush_Nfet_25A_Multi
  501. ;BESCNO EQU Turnigy_Plush_Nfet_30A_Main
  502. ;BESCNO EQU Turnigy_Plush_Nfet_30A_Tail
  503. ;BESCNO EQU Turnigy_Plush_Nfet_30A_Multi
  504. ;BESCNO EQU Turnigy_AE_20A_Main
  505. ;BESCNO EQU Turnigy_AE_20A_Tail
  506. ;BESCNO EQU Turnigy_AE_20A_Multi
  507. ;BESCNO EQU Turnigy_AE_25A_Main
  508. ;BESCNO EQU Turnigy_AE_25A_Tail
  509. ;BESCNO EQU Turnigy_AE_25A_Multi
  510. ;BESCNO EQU Turnigy_AE_30A_Main
  511. ;BESCNO EQU Turnigy_AE_30A_Tail
  512. ;BESCNO EQU Turnigy_AE_30A_Multi
  513. ;BESCNO EQU Turnigy_AE_45A_Main
  514. ;BESCNO EQU Turnigy_AE_45A_Tail
  515. ;BESCNO EQU Turnigy_AE_45A_Multi
  516. ;BESCNO EQU Turnigy_KForce_40A_Main
  517. ;BESCNO EQU Turnigy_KForce_40A_Tail
  518. ;BESCNO EQU Turnigy_KForce_40A_Multi
  519. ;BESCNO EQU Turnigy_KForce_70A_HV_Main
  520. ;BESCNO EQU Turnigy_KForce_70A_HV_Tail
  521. ;BESCNO EQU Turnigy_KForce_70A_HV_Multi
  522. ;BESCNO EQU Turnigy_KForce_120A_HV_Main
  523. ;BESCNO EQU Turnigy_KForce_120A_HV_Tail
  524. ;BESCNO EQU Turnigy_KForce_120A_HV_Multi
  525. ;BESCNO EQU Turnigy_KForce_120A_HV_v2_Main
  526. ;BESCNO EQU Turnigy_KForce_120A_HV_v2_Tail
  527. ;BESCNO EQU Turnigy_KForce_120A_HV_v2_Multi
  528. ;BESCNO EQU Skywalker_20A_Main
  529. ;BESCNO EQU Skywalker_20A_Tail
  530. ;BESCNO EQU Skywalker_20A_Multi
  531. ;BESCNO EQU Skywalker_40A_Main
  532. ;BESCNO EQU Skywalker_40A_Tail
  533. ;BESCNO EQU Skywalker_40A_Multi
  534. ;BESCNO EQU HiModel_Cool_22A_Main
  535. ;BESCNO EQU HiModel_Cool_22A_Tail
  536. ;BESCNO EQU HiModel_Cool_22A_Multi
  537. ;BESCNO EQU HiModel_Cool_33A_Main
  538. ;BESCNO EQU HiModel_Cool_33A_Tail
  539. ;BESCNO EQU HiModel_Cool_33A_Multi
  540. ;BESCNO EQU HiModel_Cool_41A_Main
  541. ;BESCNO EQU HiModel_Cool_41A_Tail
  542. ;BESCNO EQU HiModel_Cool_41A_Multi
  543. ;BESCNO EQU RCTimer_6A_Main
  544. ;BESCNO EQU RCTimer_6A_Tail
  545. ;BESCNO EQU RCTimer_6A_Multi
  546. ;BESCNO EQU Align_RCE_BL15X_Main
  547. ;BESCNO EQU Align_RCE_BL15X_Tail
  548. ;BESCNO EQU Align_RCE_BL15X_Multi
  549. ;BESCNO EQU Align_RCE_BL15P_Main
  550. ;BESCNO EQU Align_RCE_BL15P_Tail
  551. ;BESCNO EQU Align_RCE_BL15P_Multi
  552. ;BESCNO EQU Align_RCE_BL35X_Main
  553. ;BESCNO EQU Align_RCE_BL35X_Tail
  554. ;BESCNO EQU Align_RCE_BL35X_Multi
  555. ;BESCNO EQU Align_RCE_BL35P_Main
  556. ;BESCNO EQU Align_RCE_BL35P_Tail
  557. ;BESCNO EQU Align_RCE_BL35P_Multi
  558. ;BESCNO EQU Gaui_GE_183_18A_Main
  559. ;BESCNO EQU Gaui_GE_183_18A_Tail
  560. ;BESCNO EQU Gaui_GE_183_18A_Multi
  561. ;BESCNO EQU H_King_10A_Main
  562. ;BESCNO EQU H_King_10A_Tail
  563. ;BESCNO EQU H_King_10A_Multi
  564. ;BESCNO EQU H_King_20A_Main
  565. ;BESCNO EQU H_King_20A_Tail
  566. ;BESCNO EQU H_King_20A_Multi
  567. ;BESCNO EQU H_King_35A_Main
  568. ;BESCNO EQU H_King_35A_Tail
  569. ;BESCNO EQU H_King_35A_Multi
  570. ;BESCNO EQU H_King_50A_Main
  571. ;BESCNO EQU H_King_50A_Tail
  572. ;BESCNO EQU H_King_50A_Multi
  573. ;BESCNO EQU Polaris_Thunder_12A_Main
  574. ;BESCNO EQU Polaris_Thunder_12A_Tail
  575. ;BESCNO EQU Polaris_Thunder_12A_Multi
  576. ;BESCNO EQU Polaris_Thunder_20A_Main
  577. ;BESCNO EQU Polaris_Thunder_20A_Tail
  578. ;BESCNO EQU Polaris_Thunder_20A_Multi
  579. ;BESCNO EQU Polaris_Thunder_30A_Main
  580. ;BESCNO EQU Polaris_Thunder_30A_Tail
  581. ;BESCNO EQU Polaris_Thunder_30A_Multi
  582. ;BESCNO EQU Polaris_Thunder_40A_Main
  583. ;BESCNO EQU Polaris_Thunder_40A_Tail
  584. ;BESCNO EQU Polaris_Thunder_40A_Multi
  585. ;BESCNO EQU Polaris_Thunder_60A_Main
  586. ;BESCNO EQU Polaris_Thunder_60A_Tail
  587. ;BESCNO EQU Polaris_Thunder_60A_Multi
  588. ;BESCNO EQU Polaris_Thunder_80A_Main
  589. ;BESCNO EQU Polaris_Thunder_80A_Tail
  590. ;BESCNO EQU Polaris_Thunder_80A_Multi
  591. ;BESCNO EQU Polaris_Thunder_100A_Main
  592. ;BESCNO EQU Polaris_Thunder_100A_Tail
  593. ;BESCNO EQU Polaris_Thunder_100A_Multi
  594. ;BESCNO EQU Platinum_Pro_30A_Main
  595. ;BESCNO EQU Platinum_Pro_30A_Tail
  596. ;BESCNO EQU Platinum_Pro_30A_Multi
  597. ;BESCNO EQU Platinum_Pro_150A_Main
  598. ;BESCNO EQU Platinum_Pro_150A_Tail
  599. ;BESCNO EQU Platinum_Pro_150A_Multi
  600. ;BESCNO EQU Platinum_50Av3_Main
  601. ;BESCNO EQU Platinum_50Av3_Tail
  602. ;BESCNO EQU Platinum_50Av3_Multi
  603. ;BESCNO EQU EAZY_3Av2_Main
  604. ;BESCNO EQU EAZY_3Av2_Tail
  605. ;BESCNO EQU EAZY_3Av2_Multi
  606. ;BESCNO EQU Tarot_30A_Main
  607. ;BESCNO EQU Tarot_30A_Tail
  608. ;BESCNO EQU Tarot_30A_Multi
  609. ;BESCNO EQU SkyIII_30A_Main
  610. ;BESCNO EQU SkyIII_30A_Tail
  611. ;BESCNO EQU SkyIII_30A_Multi
  612. ;BESCNO EQU EMAX_20A_Main
  613. ;BESCNO EQU EMAX_20A_Tail
  614. ;BESCNO EQU EMAX_20A_Multi
  615. ;BESCNO EQU EMAX_40A_Main
  616. ;BESCNO EQU EMAX_40A_Tail
  617. ;BESCNO EQU EMAX_40A_Multi
  618. ;BESCNO EQU XRotor_10A_Main
  619. ;BESCNO EQU XRotor_10A_Tail
  620. ;BESCNO EQU XRotor_10A_Multi
  621. ;BESCNO EQU XRotor_20A_Main
  622. ;BESCNO EQU XRotor_20A_Tail
  623. ;BESCNO EQU XRotor_20A_Multi
  624. ;BESCNO EQU XRotor_40A_Main
  625. ;BESCNO EQU XRotor_40A_Tail
  626. ;BESCNO EQU XRotor_40A_Multi
  627. ;**** **** **** **** ****
  628. ; ESC selection statements
  629. IF BESCNO == XP_3A_Main
  630. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  631. $include (XP_3A.inc) ; Select XP 3A pinout
  632. ENDIF
  633. IF BESCNO == XP_3A_Tail
  634. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  635. $include (XP_3A.inc) ; Select XP 3A pinout
  636. ENDIF
  637. IF BESCNO == XP_3A_Multi
  638. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  639. $include (XP_3A.inc) ; Select XP 3A pinout
  640. ENDIF
  641. IF BESCNO == XP_7A_Main
  642. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  643. $include (XP_7A.inc) ; Select XP 7A pinout
  644. ENDIF
  645. IF BESCNO == XP_7A_Tail
  646. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  647. $include (XP_7A.inc) ; Select XP 7A pinout
  648. ENDIF
  649. IF BESCNO == XP_7A_Multi
  650. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  651. $include (XP_7A.inc) ; Select XP 7A pinout
  652. ENDIF
  653. IF BESCNO == XP_7A_Fast_Main
  654. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  655. $include (XP_7A_Fast.inc) ; Select XP 7A Fast pinout
  656. ENDIF
  657. IF BESCNO == XP_7A_Fast_Tail
  658. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  659. $include (XP_7A_Fast.inc) ; Select XP 7A Fast pinout
  660. ENDIF
  661. IF BESCNO == XP_7A_Fast_Multi
  662. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  663. $include (XP_7A_Fast.inc) ; Select XP 7A Fast pinout
  664. ENDIF
  665. IF BESCNO == XP_12A_Main
  666. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  667. $include (XP_12A.inc) ; Select XP 12A pinout
  668. ENDIF
  669. IF BESCNO == XP_12A_Tail
  670. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  671. $include (XP_12A.inc) ; Select XP 12A pinout
  672. ENDIF
  673. IF BESCNO == XP_12A_Multi
  674. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  675. $include (XP_12A.inc) ; Select XP 12A pinout
  676. ENDIF
  677. IF BESCNO == XP_18A_Main
  678. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  679. $include (XP_18A.inc) ; Select XP 18A pinout
  680. ENDIF
  681. IF BESCNO == XP_18A_Tail
  682. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  683. $include (XP_18A.inc) ; Select XP 18A pinout
  684. ENDIF
  685. IF BESCNO == XP_18A_Multi
  686. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  687. $include (XP_18A.inc) ; Select XP 18A pinout
  688. ENDIF
  689. IF BESCNO == XP_25A_Main
  690. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  691. $include (XP_25A.inc) ; Select XP 25A pinout
  692. ENDIF
  693. IF BESCNO == XP_25A_Tail
  694. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  695. $include (XP_25A.inc) ; Select XP 25A pinout
  696. ENDIF
  697. IF BESCNO == XP_25A_Multi
  698. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  699. $include (XP_25A.inc) ; Select XP 25A pinout
  700. ENDIF
  701. IF BESCNO == XP_35A_SW_Main
  702. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  703. $include (XP_35A_SW.inc) ; Select XP 35A SW pinout
  704. ENDIF
  705. IF BESCNO == XP_35A_SW_Tail
  706. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  707. $include (XP_35A_SW.inc) ; Select XP 35A SW pinout
  708. ENDIF
  709. IF BESCNO == XP_35A_SW_Multi
  710. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  711. $include (XP_35A_SW.inc) ; Select XP 35A SW pinout
  712. ENDIF
  713. IF BESCNO == DP_3A_Main
  714. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  715. $include (DP_3A.inc) ; Select DP 3A pinout
  716. ENDIF
  717. IF BESCNO == DP_3A_Tail
  718. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  719. $include (DP_3A.inc) ; Select DP 3A pinout
  720. ENDIF
  721. IF BESCNO == DP_3A_Multi
  722. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  723. $include (DP_3A.inc) ; Select DP 3A pinout
  724. ENDIF
  725. IF BESCNO == Supermicro_3p5A_Main
  726. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  727. $include (Supermicro_3p5A.inc) ; Select Supermicro 3.5A pinout
  728. ENDIF
  729. IF BESCNO == Supermicro_3p5A_Tail
  730. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  731. $include (Supermicro_3p5A.inc) ; Select Supermicro 3.5A pinout
  732. ENDIF
  733. IF BESCNO == Supermicro_3p5A_Multi
  734. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  735. $include (Supermicro_3p5A.inc) ; Select Supermicro 3.5A pinout
  736. ENDIF
  737. IF BESCNO == Turnigy_Plush_6A_Main
  738. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  739. $include (Turnigy_Plush_6A.inc) ; Select Turnigy Plush 6A pinout
  740. ENDIF
  741. IF BESCNO == Turnigy_Plush_6A_Tail
  742. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  743. $include (Turnigy_Plush_6A.inc) ; Select Turnigy Plush 6A pinout
  744. ENDIF
  745. IF BESCNO == Turnigy_Plush_6A_Multi
  746. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  747. $include (Turnigy_Plush_6A.inc) ; Select Turnigy Plush 6A pinout
  748. ENDIF
  749. IF BESCNO == Turnigy_Plush_10A_Main
  750. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  751. $include (Turnigy_Plush_10A.inc) ; Select Turnigy Plush 10A pinout
  752. ENDIF
  753. IF BESCNO == Turnigy_Plush_10A_Tail
  754. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  755. $include (Turnigy_Plush_10A.inc) ; Select Turnigy Plush 10A pinout
  756. ENDIF
  757. IF BESCNO == Turnigy_Plush_10A_Multi
  758. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  759. $include (Turnigy_Plush_10A.inc) ; Select Turnigy Plush 10A pinout
  760. ENDIF
  761. IF BESCNO == Turnigy_Plush_12A_Main
  762. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  763. $include (Turnigy_Plush_12A.inc) ; Select Turnigy Plush 12A pinout
  764. ENDIF
  765. IF BESCNO == Turnigy_Plush_12A_Tail
  766. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  767. $include (Turnigy_Plush_12A.inc) ; Select Turnigy Plush 12A pinout
  768. ENDIF
  769. IF BESCNO == Turnigy_Plush_12A_Multi
  770. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  771. $include (Turnigy_Plush_12A.inc) ; Select Turnigy Plush 12A pinout
  772. ENDIF
  773. IF BESCNO == Turnigy_Plush_18A_Main
  774. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  775. $include (Turnigy_Plush_18A.inc) ; Select Turnigy Plush 18A pinout
  776. ENDIF
  777. IF BESCNO == Turnigy_Plush_18A_Tail
  778. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  779. $include (Turnigy_Plush_18A.inc) ; Select Turnigy Plush 18A pinout
  780. ENDIF
  781. IF BESCNO == Turnigy_Plush_18A_Multi
  782. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  783. $include (Turnigy_Plush_18A.inc) ; Select Turnigy Plush 18A pinout
  784. ENDIF
  785. IF BESCNO == Turnigy_Plush_25A_Main
  786. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  787. $include (Turnigy_Plush_25A.inc) ; Select Turnigy Plush 25A pinout
  788. ENDIF
  789. IF BESCNO == Turnigy_Plush_25A_Tail
  790. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  791. $include (Turnigy_Plush_25A.inc) ; Select Turnigy Plush 25A pinout
  792. ENDIF
  793. IF BESCNO == Turnigy_Plush_25A_Multi
  794. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  795. $include (Turnigy_Plush_25A.inc) ; Select Turnigy Plush 25A pinout
  796. ENDIF
  797. IF BESCNO == Turnigy_Plush_30A_Main
  798. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  799. $include (Turnigy_Plush_30A.inc) ; Select Turnigy Plush 30A pinout
  800. ENDIF
  801. IF BESCNO == Turnigy_Plush_30A_Tail
  802. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  803. $include (Turnigy_Plush_30A.inc) ; Select Turnigy Plush 30A pinout
  804. ENDIF
  805. IF BESCNO == Turnigy_Plush_30A_Multi
  806. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  807. $include (Turnigy_Plush_30A.inc) ; Select Turnigy Plush 30A pinout
  808. ENDIF
  809. IF BESCNO == Turnigy_Plush_40A_Main
  810. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  811. $include (Turnigy_Plush_40A.inc) ; Select Turnigy Plush 40A pinout
  812. ENDIF
  813. IF BESCNO == Turnigy_Plush_40A_Tail
  814. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  815. $include (Turnigy_Plush_40A.inc) ; Select Turnigy Plush 40A pinout
  816. ENDIF
  817. IF BESCNO == Turnigy_Plush_40A_Multi
  818. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  819. $include (Turnigy_Plush_40A.inc) ; Select Turnigy Plush 40A pinout
  820. ENDIF
  821. IF BESCNO == Turnigy_Plush_60A_Main
  822. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  823. $include (Turnigy_Plush_60A.inc) ; Select Turnigy Plush 60A pinout
  824. ENDIF
  825. IF BESCNO == Turnigy_Plush_60A_Tail
  826. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  827. $include (Turnigy_Plush_60A.inc) ; Select Turnigy Plush 60A pinout
  828. ENDIF
  829. IF BESCNO == Turnigy_Plush_60A_Multi
  830. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  831. $include (Turnigy_Plush_60A.inc) ; Select Turnigy Plush 60A pinout
  832. ENDIF
  833. IF BESCNO == Turnigy_Plush_80A_Main
  834. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  835. $include (Turnigy_Plush_80A.inc) ; Select Turnigy Plush 80A pinout
  836. ENDIF
  837. IF BESCNO == Turnigy_Plush_80A_Tail
  838. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  839. $include (Turnigy_Plush_80A.inc) ; Select Turnigy Plush 80A pinout
  840. ENDIF
  841. IF BESCNO == Turnigy_Plush_80A_Multi
  842. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  843. $include (Turnigy_Plush_80A.inc) ; Select Turnigy Plush 80A pinout
  844. ENDIF
  845. IF BESCNO == Turnigy_Plush_Nfet_18A_Main
  846. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  847. $include (Turnigy_Plush_Nfet_18A.inc) ; Select Turnigy Plush Nfet 18A pinout
  848. ENDIF
  849. IF BESCNO == Turnigy_Plush_Nfet_18A_Tail
  850. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  851. $include (Turnigy_Plush_Nfet_18A.inc) ; Select Turnigy Plush Nfet 18A pinout
  852. ENDIF
  853. IF BESCNO == Turnigy_Plush_Nfet_18A_Multi
  854. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  855. $include (Turnigy_Plush_Nfet_18A.inc) ; Select Turnigy Plush Nfet 18A pinout
  856. ENDIF
  857. IF BESCNO == Turnigy_Plush_Nfet_25A_Main
  858. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  859. $include (Turnigy_Plush_Nfet_25A.inc) ; Select Turnigy Plush Nfet 25A pinout
  860. ENDIF
  861. IF BESCNO == Turnigy_Plush_Nfet_25A_Tail
  862. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  863. $include (Turnigy_Plush_Nfet_25A.inc) ; Select Turnigy Plush Nfet 25A pinout
  864. ENDIF
  865. IF BESCNO == Turnigy_Plush_Nfet_25A_Multi
  866. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  867. $include (Turnigy_Plush_Nfet_25A.inc) ; Select Turnigy Plush Nfet 25A pinout
  868. ENDIF
  869. IF BESCNO == Turnigy_Plush_Nfet_30A_Main
  870. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  871. $include (Turnigy_Plush_Nfet_30A.inc) ; Select Turnigy Plush Nfet 30A pinout
  872. ENDIF
  873. IF BESCNO == Turnigy_Plush_Nfet_30A_Tail
  874. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  875. $include (Turnigy_Plush_Nfet_30A.inc) ; Select Turnigy Plush Nfet 30A pinout
  876. ENDIF
  877. IF BESCNO == Turnigy_Plush_Nfet_30A_Multi
  878. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  879. $include (Turnigy_Plush_Nfet_30A.inc) ; Select Turnigy Plush Nfet 30A pinout
  880. ENDIF
  881. IF BESCNO == Turnigy_AE_20A_Main
  882. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  883. $include (Turnigy_AE_20A.inc) ; Select Turnigy AE-20A pinout
  884. ENDIF
  885. IF BESCNO == Turnigy_AE_20A_Tail
  886. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  887. $include (Turnigy_AE_20A.inc) ; Select Turnigy AE-20A pinout
  888. ENDIF
  889. IF BESCNO == Turnigy_AE_20A_Multi
  890. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  891. $include (Turnigy_AE_20A.inc) ; Select Turnigy AE-20A pinout
  892. ENDIF
  893. IF BESCNO == Turnigy_AE_25A_Main
  894. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  895. $include (Turnigy_AE_25A.inc) ; Select Turnigy AE-25A pinout
  896. ENDIF
  897. IF BESCNO == Turnigy_AE_25A_Tail
  898. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  899. $include (Turnigy_AE_25A.inc) ; Select Turnigy AE-25A pinout
  900. ENDIF
  901. IF BESCNO == Turnigy_AE_25A_Multi
  902. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  903. $include (Turnigy_AE_25A.inc) ; Select Turnigy AE-25A pinout
  904. ENDIF
  905. IF BESCNO == Turnigy_AE_30A_Main
  906. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  907. $include (Turnigy_AE_30A.inc) ; Select Turnigy AE-30A pinout
  908. ENDIF
  909. IF BESCNO == Turnigy_AE_30A_Tail
  910. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  911. $include (Turnigy_AE_30A.inc) ; Select Turnigy AE-30A pinout
  912. ENDIF
  913. IF BESCNO == Turnigy_AE_30A_Multi
  914. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  915. $include (Turnigy_AE_30A.inc) ; Select Turnigy AE-30A pinout
  916. ENDIF
  917. IF BESCNO == Turnigy_AE_45A_Main
  918. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  919. $include (Turnigy_AE_45A.inc) ; Select Turnigy AE-45A pinout
  920. ENDIF
  921. IF BESCNO == Turnigy_AE_45A_Tail
  922. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  923. $include (Turnigy_AE_45A.inc) ; Select Turnigy AE-45A pinout
  924. ENDIF
  925. IF BESCNO == Turnigy_AE_45A_Multi
  926. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  927. $include (Turnigy_AE_45A.inc) ; Select Turnigy AE-45A pinout
  928. ENDIF
  929. IF BESCNO == Turnigy_KForce_40A_Main
  930. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  931. $include (Turnigy_KForce_40A.inc) ; Select Turnigy KForce 40A pinout
  932. ENDIF
  933. IF BESCNO == Turnigy_KForce_40A_Tail
  934. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  935. $include (Turnigy_KForce_40A.inc) ; Select Turnigy KForce 40A pinout
  936. ENDIF
  937. IF BESCNO == Turnigy_KForce_40A_Multi
  938. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  939. $include (Turnigy_KForce_40A.inc) ; Select Turnigy KForce 40A pinout
  940. ENDIF
  941. IF BESCNO == Turnigy_KForce_70A_HV_Main
  942. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  943. $include (Turnigy_KForce_70A_HV.inc) ; Select Turnigy KForce 70A HV pinout
  944. ENDIF
  945. IF BESCNO == Turnigy_KForce_70A_HV_Tail
  946. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  947. $include (Turnigy_KForce_70A_HV.inc) ; Select Turnigy KForce 70A HV pinout
  948. ENDIF
  949. IF BESCNO == Turnigy_KForce_70A_HV_Multi
  950. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  951. $include (Turnigy_KForce_70A_HV.inc) ; Select Turnigy KForce 70A HV pinout
  952. ENDIF
  953. IF BESCNO == Turnigy_KForce_120A_HV_Main
  954. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  955. $include (Turnigy_KForce_120A_HV.inc) ; Select Turnigy KForce 120A HV pinout
  956. ENDIF
  957. IF BESCNO == Turnigy_KForce_120A_HV_Tail
  958. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  959. $include (Turnigy_KForce_120A_HV.inc) ; Select Turnigy KForce 120A HV pinout
  960. ENDIF
  961. IF BESCNO == Turnigy_KForce_120A_HV_Multi
  962. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  963. $include (Turnigy_KForce_120A_HV.inc) ; Select Turnigy KForce 120A HV pinout
  964. ENDIF
  965. IF BESCNO == Turnigy_KForce_120A_HV_v2_Main
  966. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  967. $include (Turnigy_KForce_120A_HV_v2.inc); Select Turnigy KForce 120A HV v2 pinout
  968. ENDIF
  969. IF BESCNO == Turnigy_KForce_120A_HV_v2_Tail
  970. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  971. $include (Turnigy_KForce_120A_HV_v2.inc); Select Turnigy KForce 120A HV v2 pinout
  972. ENDIF
  973. IF BESCNO == Turnigy_KForce_120A_HV_v2_Multi
  974. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  975. $include (Turnigy_KForce_120A_HV_v2.inc); Select Turnigy KForce 120A HV v2 pinout
  976. ENDIF
  977. IF BESCNO == Skywalker_20A_Main
  978. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  979. $include (Skywalker_20A.inc) ; Select Skywalker 20A pinout
  980. ENDIF
  981. IF BESCNO == Skywalker_20A_Tail
  982. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  983. $include (Skywalker_20A.inc) ; Select Skywalker 20A pinout
  984. ENDIF
  985. IF BESCNO == Skywalker_20A_Multi
  986. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  987. $include (Skywalker_20A.inc) ; Select Skywalker 20A pinout
  988. ENDIF
  989. IF BESCNO == Skywalker_40A_Main
  990. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  991. $include (Skywalker_40A.inc) ; Select Skywalker 40A pinout
  992. ENDIF
  993. IF BESCNO == Skywalker_40A_Tail
  994. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  995. $include (Skywalker_40A.inc) ; Select Skywalker 40A pinout
  996. ENDIF
  997. IF BESCNO == Skywalker_40A_Multi
  998. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  999. $include (Skywalker_40A.inc) ; Select Skywalker 40A pinout
  1000. ENDIF
  1001. IF BESCNO == HiModel_Cool_22A_Main
  1002. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1003. $include (HiModel_Cool_22A.inc) ; Select HiModel Cool 22A pinout
  1004. ENDIF
  1005. IF BESCNO == HiModel_Cool_22A_Tail
  1006. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1007. $include (HiModel_Cool_22A.inc) ; Select HiModel Cool 22A pinout
  1008. ENDIF
  1009. IF BESCNO == HiModel_Cool_22A_Multi
  1010. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1011. $include (HiModel_Cool_22A.inc) ; Select HiModel Cool 22A pinout
  1012. ENDIF
  1013. IF BESCNO == HiModel_Cool_33A_Main
  1014. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1015. $include (HiModel_Cool_33A.inc) ; Select HiModel Cool 33A pinout
  1016. ENDIF
  1017. IF BESCNO == HiModel_Cool_33A_Tail
  1018. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1019. $include (HiModel_Cool_33A.inc) ; Select HiModel Cool 33A pinout
  1020. ENDIF
  1021. IF BESCNO == HiModel_Cool_33A_Multi
  1022. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1023. $include (HiModel_Cool_33A.inc) ; Select HiModel Cool 33A pinout
  1024. ENDIF
  1025. IF BESCNO == HiModel_Cool_41A_Main
  1026. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1027. $include (HiModel_Cool_41A.inc) ; Select HiModel Cool 41A pinout
  1028. ENDIF
  1029. IF BESCNO == HiModel_Cool_41A_Tail
  1030. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1031. $include (HiModel_Cool_41A.inc) ; Select HiModel Cool 41A pinout
  1032. ENDIF
  1033. IF BESCNO == HiModel_Cool_41A_Multi
  1034. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1035. $include (HiModel_Cool_41A.inc) ; Select HiModel Cool 41A pinout
  1036. ENDIF
  1037. IF BESCNO == RCTimer_6A_Main
  1038. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1039. $include (RCTimer_6A.inc) ; Select RC Timer 6A pinout
  1040. ENDIF
  1041. IF BESCNO == RCTimer_6A_Tail
  1042. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1043. $include (RCTimer_6A.inc) ; Select RC Timer 6A pinout
  1044. ENDIF
  1045. IF BESCNO == RCTimer_6A_Multi
  1046. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1047. $include (RCTimer_6A.inc) ; Select RC Timer 6A pinout
  1048. ENDIF
  1049. IF BESCNO == Align_RCE_BL15X_Main
  1050. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1051. $include (Align_RCE_BL15X.inc) ; Select Align RCE-BL15X pinout
  1052. ENDIF
  1053. IF BESCNO == Align_RCE_BL15X_Tail
  1054. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1055. $include (Align_RCE_BL15X.inc) ; Select Align RCE-BL15X pinout
  1056. ENDIF
  1057. IF BESCNO == Align_RCE_BL15X_Multi
  1058. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1059. $include (Align_RCE_BL15X.inc) ; Select Align RCE-BL15X pinout
  1060. ENDIF
  1061. IF BESCNO == Align_RCE_BL15P_Main
  1062. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1063. $include (Align_RCE_BL15P.inc) ; Select Align RCE-BL15P pinout
  1064. ENDIF
  1065. IF BESCNO == Align_RCE_BL15P_Tail
  1066. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1067. $include (Align_RCE_BL15P.inc) ; Select Align RCE-BL15P pinout
  1068. ENDIF
  1069. IF BESCNO == Align_RCE_BL15P_Multi
  1070. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1071. $include (Align_RCE_BL15P.inc) ; Select Align RCE-BL15P pinout
  1072. ENDIF
  1073. IF BESCNO == Align_RCE_BL35X_Main
  1074. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1075. $include (Align_RCE_BL35X.inc) ; Select Align RCE-BL35X pinout
  1076. ENDIF
  1077. IF BESCNO == Align_RCE_BL35X_Tail
  1078. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1079. $include (Align_RCE_BL35X.inc) ; Select Align RCE-BL35X pinout
  1080. ENDIF
  1081. IF BESCNO == Align_RCE_BL35X_Multi
  1082. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1083. $include (Align_RCE_BL35X.inc) ; Select Align RCE-BL35X pinout
  1084. ENDIF
  1085. IF BESCNO == Align_RCE_BL35P_Main
  1086. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1087. $include (Align_RCE_BL35P.inc) ; Select Align RCE-BL35P pinout
  1088. ENDIF
  1089. IF BESCNO == Align_RCE_BL35P_Tail
  1090. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1091. $include (Align_RCE_BL35P.inc) ; Select Align RCE-BL35P pinout
  1092. ENDIF
  1093. IF BESCNO == Align_RCE_BL35P_Multi
  1094. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1095. $include (Align_RCE_BL35P.inc) ; Select Align RCE-BL35P pinout
  1096. ENDIF
  1097. IF BESCNO == Gaui_GE_183_18A_Main
  1098. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1099. $include (Gaui_GE_183_18A.inc) ; Select Gaui GE-183 18A pinout
  1100. ENDIF
  1101. IF BESCNO == Gaui_GE_183_18A_Tail
  1102. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1103. $include (Gaui_GE_183_18A.inc) ; Select Gaui GE-183 18A pinout
  1104. ENDIF
  1105. IF BESCNO == Gaui_GE_183_18A_Multi
  1106. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1107. $include (Gaui_GE_183_18A.inc) ; Select Gaui GE-183 18A pinout
  1108. ENDIF
  1109. IF BESCNO == H_King_10A_Main
  1110. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1111. $include (H_King_10A.inc) ; Select H-King 10A pinout
  1112. ENDIF
  1113. IF BESCNO == H_King_10A_Tail
  1114. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1115. $include (H_King_10A.inc) ; Select H-King 10A pinout
  1116. ENDIF
  1117. IF BESCNO == H_King_10A_Multi
  1118. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1119. $include (H_King_10A.inc) ; Select H-King 10A pinout
  1120. ENDIF
  1121. IF BESCNO == H_King_20A_Main
  1122. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1123. $include (H_King_20A.inc) ; Select H-King 20A pinout
  1124. ENDIF
  1125. IF BESCNO == H_King_20A_Tail
  1126. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1127. $include (H_King_20A.inc) ; Select H-King 20A pinout
  1128. ENDIF
  1129. IF BESCNO == H_King_20A_Multi
  1130. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1131. $include (H_King_20A.inc) ; Select H-King 20A pinout
  1132. ENDIF
  1133. IF BESCNO == H_King_35A_Main
  1134. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1135. $include (H_King_35A.inc) ; Select H-King 35A pinout
  1136. ENDIF
  1137. IF BESCNO == H_King_35A_Tail
  1138. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1139. $include (H_King_35A.inc) ; Select H-King 35A pinout
  1140. ENDIF
  1141. IF BESCNO == H_King_35A_Multi
  1142. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1143. $include (H_King_35A.inc) ; Select H-King 35A pinout
  1144. ENDIF
  1145. IF BESCNO == H_King_50A_Main
  1146. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1147. $include (H_King_50A.inc) ; Select H-King 50A pinout
  1148. ENDIF
  1149. IF BESCNO == H_King_50A_Tail
  1150. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1151. $include (H_King_50A.inc) ; Select H-King 50A pinout
  1152. ENDIF
  1153. IF BESCNO == H_King_50A_Multi
  1154. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1155. $include (H_King_50A.inc) ; Select H-King 50A pinout
  1156. ENDIF
  1157. IF BESCNO == Polaris_Thunder_12A_Main
  1158. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1159. $include (Polaris_Thunder_12A.inc) ; Select Polaris Thunder 12A pinout
  1160. ENDIF
  1161. IF BESCNO == Polaris_Thunder_12A_Tail
  1162. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1163. $include (Polaris_Thunder_12A.inc) ; Select Polaris Thunder 12A pinout
  1164. ENDIF
  1165. IF BESCNO == Polaris_Thunder_12A_Multi
  1166. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1167. $include (Polaris_Thunder_12A.inc) ; Select Polaris Thunder 12A pinout
  1168. ENDIF
  1169. IF BESCNO == Polaris_Thunder_20A_Main
  1170. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1171. $include (Polaris_Thunder_20A.inc) ; Select Polaris Thunder 20A pinout
  1172. ENDIF
  1173. IF BESCNO == Polaris_Thunder_20A_Tail
  1174. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1175. $include (Polaris_Thunder_20A.inc) ; Select Polaris Thunder 20A pinout
  1176. ENDIF
  1177. IF BESCNO == Polaris_Thunder_20A_Multi
  1178. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1179. $include (Polaris_Thunder_20A.inc) ; Select Polaris Thunder 20A pinout
  1180. ENDIF
  1181. IF BESCNO == Polaris_Thunder_30A_Main
  1182. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1183. $include (Polaris_Thunder_30A.inc) ; Select Polaris Thunder 30A pinout
  1184. ENDIF
  1185. IF BESCNO == Polaris_Thunder_30A_Tail
  1186. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1187. $include (Polaris_Thunder_30A.inc) ; Select Polaris Thunder 30A pinout
  1188. ENDIF
  1189. IF BESCNO == Polaris_Thunder_30A_Multi
  1190. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1191. $include (Polaris_Thunder_30A.inc) ; Select Polaris Thunder 30A pinout
  1192. ENDIF
  1193. IF BESCNO == Polaris_Thunder_40A_Main
  1194. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1195. $include (Polaris_Thunder_40A.inc) ; Select Polaris Thunder 40A pinout
  1196. ENDIF
  1197. IF BESCNO == Polaris_Thunder_40A_Tail
  1198. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1199. $include (Polaris_Thunder_40A.inc) ; Select Polaris Thunder 40A pinout
  1200. ENDIF
  1201. IF BESCNO == Polaris_Thunder_40A_Multi
  1202. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1203. $include (Polaris_Thunder_40A.inc) ; Select Polaris Thunder 40A pinout
  1204. ENDIF
  1205. IF BESCNO == Polaris_Thunder_60A_Main
  1206. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1207. $include (Polaris_Thunder_60A.inc) ; Select Polaris Thunder 60A pinout
  1208. ENDIF
  1209. IF BESCNO == Polaris_Thunder_60A_Tail
  1210. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1211. $include (Polaris_Thunder_60A.inc) ; Select Polaris Thunder 60A pinout
  1212. ENDIF
  1213. IF BESCNO == Polaris_Thunder_60A_Multi
  1214. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1215. $include (Polaris_Thunder_60A.inc) ; Select Polaris Thunder 60A pinout
  1216. ENDIF
  1217. IF BESCNO == Polaris_Thunder_80A_Main
  1218. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1219. $include (Polaris_Thunder_80A.inc) ; Select Polaris Thunder 80A pinout
  1220. ENDIF
  1221. IF BESCNO == Polaris_Thunder_80A_Tail
  1222. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1223. $include (Polaris_Thunder_80A.inc) ; Select Polaris Thunder 80A pinout
  1224. ENDIF
  1225. IF BESCNO == Polaris_Thunder_80A_Multi
  1226. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1227. $include (Polaris_Thunder_80A.inc) ; Select Polaris Thunder 80A pinout
  1228. ENDIF
  1229. IF BESCNO == Polaris_Thunder_100A_Main
  1230. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1231. $include (Polaris_Thunder_100A.inc); Select Polaris Thunder 100A pinout
  1232. ENDIF
  1233. IF BESCNO == Polaris_Thunder_100A_Tail
  1234. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1235. $include (Polaris_Thunder_100A.inc); Select Polaris Thunder 100A pinout
  1236. ENDIF
  1237. IF BESCNO == Polaris_Thunder_100A_Multi
  1238. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1239. $include (Polaris_Thunder_100A.inc); Select Polaris Thunder 100A pinout
  1240. ENDIF
  1241. IF BESCNO == Platinum_Pro_30A_Main
  1242. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1243. $include (Platinum_Pro_30A.inc) ; Select Platinum Pro 30A pinout
  1244. ENDIF
  1245. IF BESCNO == Platinum_Pro_30A_Tail
  1246. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1247. $include (Platinum_Pro_30A.inc) ; Select Platinum Pro 30A pinout
  1248. ENDIF
  1249. IF BESCNO == Platinum_Pro_30A_Multi
  1250. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1251. $include (Platinum_Pro_30A.inc) ; Select Platinum Pro 30A pinout
  1252. ENDIF
  1253. IF BESCNO == Platinum_Pro_150A_Main
  1254. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1255. $include (Platinum_Pro_150A.inc) ; Select Platinum Pro 150A pinout
  1256. ENDIF
  1257. IF BESCNO == Platinum_Pro_150A_Tail
  1258. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1259. $include (Platinum_Pro_150A.inc) ; Select Platinum Pro 150A pinout
  1260. ENDIF
  1261. IF BESCNO == Platinum_Pro_150A_Multi
  1262. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1263. $include (Platinum_Pro_150A.inc) ; Select Platinum Pro 150A pinout
  1264. ENDIF
  1265. IF BESCNO == Platinum_50Av3_Main
  1266. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1267. $include (Platinum_50Av3.inc) ; Select Platinum 50A v3 pinout
  1268. ENDIF
  1269. IF BESCNO == Platinum_50Av3_Tail
  1270. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1271. $include (Platinum_50Av3.inc) ; Select Platinum 50A v3 pinout
  1272. ENDIF
  1273. IF BESCNO == Platinum_50Av3_Multi
  1274. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1275. $include (Platinum_50Av3.inc) ; Select Platinum 50A v3 pinout
  1276. ENDIF
  1277. IF BESCNO == EAZY_3Av2_Main
  1278. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1279. $include (EAZY_3Av2.inc) ; Select Eazy 3A v2 pinout
  1280. ENDIF
  1281. IF BESCNO == EAZY_3Av2_Tail
  1282. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1283. $include (EAZY_3Av2.inc) ; Select Eazy 3A v2 pinout
  1284. ENDIF
  1285. IF BESCNO == EAZY_3Av2_Multi
  1286. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1287. $include (EAZY_3Av2.inc) ; Select Eazy 3A v2 pinout
  1288. ENDIF
  1289. IF BESCNO == Tarot_30A_Main
  1290. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1291. $include (Tarot_30A.inc) ; Select Tarot 30A pinout
  1292. ENDIF
  1293. IF BESCNO == Tarot_30A_Tail
  1294. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1295. $include (Tarot_30A.inc) ; Select Tarot 30A pinout
  1296. ENDIF
  1297. IF BESCNO == Tarot_30A_Multi
  1298. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1299. $include (Tarot_30A.inc) ; Select Tarot 30A pinout
  1300. ENDIF
  1301. IF BESCNO == SkyIII_30A_Main
  1302. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1303. $include (SkyIII_30A.inc) ; Select SkyIII 30A pinout
  1304. ENDIF
  1305. IF BESCNO == SkyIII_30A_Tail
  1306. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1307. $include (SkyIII_30A.inc) ; Select SkyIII 30A pinout
  1308. ENDIF
  1309. IF BESCNO == SkyIII_30A_Multi
  1310. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1311. $include (SkyIII_30A.inc) ; Select SkyIII 30A pinout
  1312. ENDIF
  1313. IF BESCNO == EMAX_20A_Main
  1314. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1315. $include (EMAX_20A.inc) ; Select EMAX 20A pinout
  1316. ENDIF
  1317. IF BESCNO == EMAX_20A_Tail
  1318. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1319. $include (EMAX_20A.inc) ; Select EMAX 20A pinout
  1320. ENDIF
  1321. IF BESCNO == EMAX_20A_Multi
  1322. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1323. $include (EMAX_20A.inc) ; Select EMAX 20A pinout
  1324. ENDIF
  1325. IF BESCNO == EMAX_40A_Main
  1326. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1327. $include (EMAX_40A.inc) ; Select EMAX 40A pinout
  1328. ENDIF
  1329. IF BESCNO == EMAX_40A_Tail
  1330. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1331. $include (EMAX_40A.inc) ; Select EMAX 40A pinout
  1332. ENDIF
  1333. IF BESCNO == EMAX_40A_Multi
  1334. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1335. $include (EMAX_40A.inc) ; Select EMAX 40A pinout
  1336. ENDIF
  1337. IF BESCNO == XRotor_10A_Main
  1338. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1339. $include (XRotor_10A.inc) ; Select XRotor 10A pinout
  1340. ENDIF
  1341. IF BESCNO == XRotor_10A_Tail
  1342. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1343. $include (XRotor_10A.inc) ; Select XRotor 10A pinout
  1344. ENDIF
  1345. IF BESCNO == XRotor_10A_Multi
  1346. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1347. $include (XRotor_10A.inc) ; Select XRotor 10A pinout
  1348. ENDIF
  1349. IF BESCNO == XRotor_20A_Main
  1350. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1351. $include (XRotor_20A.inc) ; Select XRotor 20A pinout
  1352. ENDIF
  1353. IF BESCNO == XRotor_20A_Tail
  1354. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1355. $include (XRotor_20A.inc) ; Select XRotor 20A pinout
  1356. ENDIF
  1357. IF BESCNO == XRotor_20A_Multi
  1358. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1359. $include (XRotor_20A.inc) ; Select XRotor 20A pinout
  1360. ENDIF
  1361. IF BESCNO == XRotor_40A_Main
  1362. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1363. $include (XRotor_40A.inc) ; Select XRotor 40A pinout
  1364. ENDIF
  1365. IF BESCNO == XRotor_40A_Tail
  1366. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1367. $include (XRotor_40A.inc) ; Select XRotor 40A pinout
  1368. ENDIF
  1369. IF BESCNO == XRotor_40A_Multi
  1370. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1371. $include (XRotor_40A.inc) ; Select XRotor 40A pinout
  1372. ENDIF
  1373. ;**** **** **** **** ****
  1374. ; TX programming defaults
  1375. ;
  1376. ; Parameter dependencies:
  1377. ; - Governor P gain, I gain and Range is only used if one of the three governor modes is selected
  1378. ; - Governor setup target is only used if Setup governor mode is selected (or closed loop mode is on for multi)
  1379. ;
  1380. ; MAIN
  1381. DEFAULT_PGM_MAIN_P_GAIN EQU 7 ; 1=0.13 2=0.17 3=0.25 4=0.38 5=0.50 6=0.75 7=1.00 8=1.5 9=2.0 10=3.0 11=4.0 12=6.0 13=8.0
  1382. DEFAULT_PGM_MAIN_I_GAIN EQU 7 ; 1=0.13 2=0.17 3=0.25 4=0.38 5=0.50 6=0.75 7=1.00 8=1.5 9=2.0 10=3.0 11=4.0 12=6.0 13=8.0
  1383. DEFAULT_PGM_MAIN_GOVERNOR_MODE EQU 1 ; 1=Tx 2=Arm 3=Setup 4=Off
  1384. DEFAULT_PGM_MAIN_GOVERNOR_RANGE EQU 1 ; 1=High 2=Middle 3=Low
  1385. DEFAULT_PGM_MAIN_LOW_VOLTAGE_LIM EQU 4 ; 1=Off 2=3.0V/c 3=3.1V/c 4=3.2V/c 5=3.3V/c 6=3.4V/c
  1386. DEFAULT_PGM_MAIN_COMM_TIMING EQU 3 ; 1=Low 2=MediumLow 3=Medium 4=MediumHigh 5=High
  1387. IF DAMPED_MODE_ENABLE == 1
  1388. DEFAULT_PGM_MAIN_PWM_FREQ EQU 2 ; 1=High 2=Low 3=DampedLight
  1389. ELSE
  1390. DEFAULT_PGM_MAIN_PWM_FREQ EQU 2 ; 1=High 2=Low
  1391. ENDIF
  1392. DEFAULT_PGM_MAIN_DEMAG_COMP EQU 1 ; 1=Disabled 2=Low 3=High
  1393. DEFAULT_PGM_MAIN_DIRECTION EQU 1 ; 1=Normal 2=Reversed
  1394. DEFAULT_PGM_MAIN_RCP_PWM_POL EQU 1 ; 1=Positive 2=Negative
  1395. DEFAULT_PGM_MAIN_GOV_SETUP_TARGET EQU 180 ; Target for governor in setup mode. Corresponds to 70% throttle
  1396. DEFAULT_PGM_MAIN_REARM_START EQU 0 ; 1=Enabled 0=Disabled
  1397. DEFAULT_PGM_MAIN_BEEP_STRENGTH EQU 120 ; Beep strength
  1398. DEFAULT_PGM_MAIN_BEACON_STRENGTH EQU 200 ; Beacon strength
  1399. DEFAULT_PGM_MAIN_BEACON_DELAY EQU 4 ; 1=1m 2=2m 3=5m 4=10m 5=Infinite
  1400. ; TAIL
  1401. DEFAULT_PGM_TAIL_GAIN EQU 3 ; 1=0.75 2=0.88 3=1.00 4=1.12 5=1.25
  1402. DEFAULT_PGM_TAIL_IDLE_SPEED EQU 4 ; 1=Low 2=MediumLow 3=Medium 4=MediumHigh 5=High
  1403. DEFAULT_PGM_TAIL_COMM_TIMING EQU 3 ; 1=Low 2=MediumLow 3=Medium 4=MediumHigh 5=High
  1404. IF DAMPED_MODE_ENABLE == 1
  1405. DEFAULT_PGM_TAIL_PWM_FREQ EQU 3 ; 1=High 2=Low 3=DampedLight
  1406. ELSE
  1407. DEFAULT_PGM_TAIL_PWM_FREQ EQU 1 ; 1=High 2=Low
  1408. ENDIF
  1409. DEFAULT_PGM_TAIL_DEMAG_COMP EQU 1 ; 1=Disabled 2=Low 3=High
  1410. DEFAULT_PGM_TAIL_DIRECTION EQU 1 ; 1=Normal 2=Reversed 3=Bidirectional
  1411. DEFAULT_PGM_TAIL_RCP_PWM_POL EQU 1 ; 1=Positive 2=Negative
  1412. DEFAULT_PGM_TAIL_BEEP_STRENGTH EQU 250 ; Beep strength
  1413. DEFAULT_PGM_TAIL_BEACON_STRENGTH EQU 250 ; Beacon strength
  1414. DEFAULT_PGM_TAIL_BEACON_DELAY EQU 4 ; 1=1m 2=2m 3=5m 4=10m 5=Infinite
  1415. ; MULTI
  1416. DEFAULT_PGM_MULTI_P_GAIN EQU 9 ; 1=0.13 2=0.17 3=0.25 4=0.38 5=0.50 6=0.75 7=1.00 8=1.5 9=2.0 10=3.0 11=4.0 12=6.0 13=8.0
  1417. DEFAULT_PGM_MULTI_I_GAIN EQU 9 ; 1=0.13 2=0.17 3=0.25 4=0.38 5=0.50 6=0.75 7=1.00 8=1.5 9=2.0 10=3.0 11=4.0 12=6.0 13=8.0
  1418. DEFAULT_PGM_MULTI_GOVERNOR_MODE EQU 4 ; 1=HiRange 2=MidRange 3=LoRange 4=Off
  1419. DEFAULT_PGM_MULTI_GAIN EQU 3 ; 1=0.75 2=0.88 3=1.00 4=1.12 5=1.25
  1420. DEFAULT_PGM_MULTI_LOW_VOLTAGE_LIM EQU 1 ; 1=Off 2=3.0V/c 3=3.1V/c 4=3.2V/c 5=3.3V/c 6=3.4V/c
  1421. DEFAULT_PGM_MULTI_COMM_TIMING EQU 3 ; 1=Low 2=MediumLow 3=Medium 4=MediumHigh 5=High
  1422. IF DAMPED_MODE_ENABLE == 1
  1423. DEFAULT_PGM_MULTI_PWM_FREQ EQU 1 ; 1=High 2=Low 3=DampedLight
  1424. ELSE
  1425. DEFAULT_PGM_MULTI_PWM_FREQ EQU 1 ; 1=High 2=Low
  1426. ENDIF
  1427. DEFAULT_PGM_MULTI_DEMAG_COMP EQU 2 ; 1=Disabled 2=Low 3=High
  1428. DEFAULT_PGM_MULTI_DIRECTION EQU 1 ; 1=Normal 2=Reversed 3=Bidirectional
  1429. DEFAULT_PGM_MULTI_RCP_PWM_POL EQU 1 ; 1=Positive 2=Negative
  1430. DEFAULT_PGM_MULTI_BEEP_STRENGTH EQU 40 ; Beep strength
  1431. DEFAULT_PGM_MULTI_BEACON_STRENGTH EQU 80 ; Beacon strength
  1432. DEFAULT_PGM_MULTI_BEACON_DELAY EQU 4 ; 1=1m 2=2m 3=5m 4=10m 5=Infinite
  1433. ; COMMON
  1434. DEFAULT_PGM_ENABLE_TX_PROGRAM EQU 1 ; 1=Enabled 0=Disabled
  1435. DEFAULT_PGM_PPM_MIN_THROTTLE EQU 37 ; 4*37+1000=1148
  1436. DEFAULT_PGM_PPM_MAX_THROTTLE EQU 208 ; 4*208+1000=1832
  1437. DEFAULT_PGM_PPM_CENTER_THROTTLE EQU 122 ; 4*122+1000=1488 (used in bidirectional mode)
  1438. DEFAULT_PGM_BEC_VOLTAGE_HIGH EQU 0 ; 0=Low 1+= High or higher
  1439. DEFAULT_PGM_ENABLE_TEMP_PROT EQU 1 ; 1=Enabled 0=Disabled
  1440. ;**** **** **** **** ****
  1441. ; Constant definitions for main
  1442. IF MODE == 0
  1443. GOV_SPOOLRATE EQU 2 ; Number of steps for governor requested pwm per 32ms
  1444. RCP_TIMEOUT_PPM EQU 10 ; Number of timer2H overflows (about 32ms) before considering rc pulse lost
  1445. RCP_TIMEOUT EQU 64 ; Number of timer2L overflows (about 128us) before considering rc pulse lost
  1446. RCP_SKIP_RATE EQU 32 ; Number of timer2L overflows (about 128us) before reenabling rc pulse detection
  1447. RCP_MIN EQU 0 ; This is minimum RC pulse length
  1448. RCP_MAX EQU 255 ; This is maximum RC pulse length
  1449. RCP_VALIDATE EQU 2 ; Require minimum this pulse length to validate RC pulse
  1450. RCP_STOP EQU 1 ; Stop motor at or below this pulse length
  1451. RCP_STOP_LIMIT EQU 250 ; Stop motor if this many timer2H overflows (~32ms) are below stop limit
  1452. PWM_START EQU 50 ; PWM used as max power during start
  1453. COMM_TIME_RED EQU 1 ; Fixed reduction (in us) for commutation wait (to account for fixed delays)
  1454. COMM_TIME_MIN EQU 1 ; Minimum time (in us) for commutation wait
  1455. TEMP_CHECK_RATE EQU 8 ; Number of adc conversions for each check of temperature (the other conversions are used for voltage)
  1456. ENDIF
  1457. ; Constant definitions for tail
  1458. IF MODE == 1
  1459. GOV_SPOOLRATE EQU 1 ; Number of steps for governor requested pwm per 32ms
  1460. RCP_TIMEOUT_PPM EQU 10 ; Number of timer2H overflows (about 32ms) before considering rc pulse lost
  1461. RCP_TIMEOUT EQU 24 ; Number of timer2L overflows (about 128us) before considering rc pulse lost
  1462. RCP_SKIP_RATE EQU 6 ; Number of timer2L overflows (about 128us) before reenabling rc pulse detection
  1463. RCP_MIN EQU 0 ; This is minimum RC pulse length
  1464. RCP_MAX EQU 255 ; This is maximum RC pulse length
  1465. RCP_VALIDATE EQU 2 ; Require minimum this pulse length to validate RC pulse
  1466. RCP_STOP EQU 1 ; Stop motor at or below this pulse length
  1467. RCP_STOP_LIMIT EQU 130 ; Stop motor if this many timer2H overflows (~32ms) are below stop limit
  1468. PWM_START EQU 50 ; PWM used as max power during start
  1469. COMM_TIME_RED EQU 1 ; Fixed reduction (in us) for commutation wait (to account for fixed delays)
  1470. COMM_TIME_MIN EQU 1 ; Minimum time (in us) for commutation wait
  1471. TEMP_CHECK_RATE EQU 8 ; Number of adc conversions for each check of temperature (the other conversions are used for voltage)
  1472. ENDIF
  1473. ; Constant definitions for multi
  1474. IF MODE == 2
  1475. GOV_SPOOLRATE EQU 1 ; Number of steps for governor requested pwm per 32ms
  1476. RCP_TIMEOUT_PPM EQU 10 ; Number of timer2H overflows (about 32ms) before considering rc pulse lost
  1477. RCP_TIMEOUT EQU 24 ; Number of timer2L overflows (about 128us) before considering rc pulse lost
  1478. RCP_SKIP_RATE EQU 6 ; Number of timer2L overflows (about 128us) before reenabling rc pulse detection
  1479. RCP_MIN EQU 0 ; This is minimum RC pulse length
  1480. RCP_MAX EQU 255 ; This is maximum RC pulse length
  1481. RCP_VALIDATE EQU 2 ; Require minimum this pulse length to validate RC pulse
  1482. RCP_STOP EQU 1 ; Stop motor at or below this pulse length
  1483. RCP_STOP_LIMIT EQU 250 ; Stop motor if this many timer2H overflows (~32ms) are below stop limit
  1484. PWM_START EQU 50 ; PWM used as max power during start
  1485. COMM_TIME_RED EQU 1 ; Fixed reduction (in us) for commutation wait (to account for fixed delays)
  1486. COMM_TIME_MIN EQU 1 ; Minimum time (in us) for commutation wait
  1487. TEMP_CHECK_RATE EQU 8 ; Number of adc conversions for each check of temperature (the other conversions are used for voltage)
  1488. ENDIF
  1489. ;**** **** **** **** ****
  1490. ; Temporary register definitions
  1491. Temp1 EQU R0
  1492. Temp2 EQU R1
  1493. Temp3 EQU R2
  1494. Temp4 EQU R3
  1495. Temp5 EQU R4
  1496. Temp6 EQU R5
  1497. Temp7 EQU R6
  1498. Temp8 EQU R7
  1499. ;**** **** **** **** ****
  1500. ; Register definitions
  1501. DSEG AT 20h ; Variables segment
  1502. Bit_Access: DS 1 ; MUST BE AT THIS ADDRESS. Variable at bit accessible address (for non interrupt routines)
  1503. Bit_Access_Int: DS 1 ; Variable at bit accessible address (for interrupts)
  1504. Requested_Pwm: DS 1 ; Requested pwm (from RC pulse value)
  1505. Governor_Req_Pwm: DS 1 ; Governor requested pwm (sets governor target)
  1506. Current_Pwm: DS 1 ; Current pwm
  1507. Current_Pwm_Limited: DS 1 ; Current pwm that is limited (applied to the motor output)
  1508. Rcp_Prev_Edge_L: DS 1 ; RC pulse previous edge timer3 timestamp (lo byte)
  1509. Rcp_Prev_Edge_H: DS 1 ; RC pulse previous edge timer3 timestamp (hi byte)
  1510. Rcp_Outside_Range_Cnt: DS 1 ; RC pulse outside range counter (incrementing)
  1511. Rcp_Timeout_Cnt: DS 1 ; RC pulse timeout counter (decrementing)
  1512. Rcp_Skip_Cnt: DS 1 ; RC pulse skip counter (decrementing)
  1513. _Spare_Reg: DS 1 ; Spare register
  1514. Flags0: DS 1 ; State flags. Reset upon init_start
  1515. T3_PENDING EQU 0 ; Timer3 pending flag
  1516. RCP_MEAS_PWM_FREQ EQU 1 ; Measure RC pulse pwm frequency
  1517. PWM_ON EQU 2 ; Set in on part of pwm cycle
  1518. PWM_TIMER0_OVERFLOW EQU 3 ; Set for 50MHz MCUs when PWM timer 0 overflows
  1519. DEMAG_ENABLED EQU 4 ; Set when demag compensation is enabled (above a min speed and throttle)
  1520. DEMAG_DETECTED EQU 5 ; Set when excessive demag time is detected
  1521. DEMAG_CUT_POWER EQU 6 ; Set when demag compensation cuts power
  1522. ; EQU 7
  1523. Flags1: DS 1 ; State flags. Reset upon init_start
  1524. MOTOR_SPINNING EQU 0 ; Set when in motor is spinning
  1525. STARTUP_PHASE EQU 1 ; Set when in startup phase
  1526. INITIAL_RUN_PHASE EQU 2 ; Set when in initial run phase, before synchronized run is achieved
  1527. DIR_CHANGE_BRAKE EQU 3 ; Set when braking before direction change
  1528. ; EQU 4
  1529. ; EQU 5
  1530. ; EQU 6
  1531. ; EQU 7
  1532. Flags2: DS 1 ; State flags. NOT reset upon init_start
  1533. RCP_UPDATED EQU 0 ; New RC pulse length value available
  1534. RCP_EDGE_NO EQU 1 ; RC pulse edge no. 0=rising, 1=falling
  1535. PGM_PWMOFF_DAMPED EQU 2 ; Programmed pwm off damped mode
  1536. PGM_PWM_HIGH_FREQ EQU 3 ; Progremmed pwm high frequency
  1537. RCP_PPM EQU 4 ; RC pulse ppm type input (set also when oneshot is set)
  1538. RCP_PPM_ONESHOT125 EQU 5 ; RC pulse ppm type input is OneShot125
  1539. ; EQU 6
  1540. ; EQU 7
  1541. Flags3: DS 1 ; State flags. NOT reset upon init_start
  1542. RCP_PWM_FREQ_1KHZ EQU 0 ; RC pulse pwm frequency is 1kHz
  1543. RCP_PWM_FREQ_2KHZ EQU 1 ; RC pulse pwm frequency is 2kHz
  1544. RCP_PWM_FREQ_4KHZ EQU 2 ; RC pulse pwm frequency is 4kHz
  1545. RCP_PWM_FREQ_8KHZ EQU 3 ; RC pulse pwm frequency is 8kHz
  1546. RCP_PWM_FREQ_12KHZ EQU 4 ; RC pulse pwm frequency is 12kHz
  1547. PGM_DIR_REV EQU 5 ; Programmed direction. 0=normal, 1=reversed
  1548. PGM_RCP_PWM_POL EQU 6 ; Programmed RC pulse pwm polarity. 0=positive, 1=negative
  1549. FULL_THROTTLE_RANGE EQU 7 ; When set full throttle range is used (1000-2000us) and stored calibration values are ignored
  1550. ;**** **** **** **** ****
  1551. ; RAM definitions
  1552. DSEG AT 30h ; Ram data segment, direct addressing
  1553. Initial_Arm: DS 1 ; Variable that is set during the first arm sequence after power on
  1554. Power_On_Wait_Cnt_L: DS 1 ; Power on wait counter (lo byte)
  1555. Power_On_Wait_Cnt_H: DS 1 ; Power on wait counter (hi byte)
  1556. Startup_Rot_Cnt: DS 1 ; Startup phase rotations counter
  1557. Startup_Ok_Cnt: DS 1 ; Startup phase ok comparator waits counter (incrementing)
  1558. Demag_Detected_Metric: DS 1 ; Metric used to gauge demag event frequency
  1559. Demag_Pwr_Off_Thresh: DS 1 ; Metric threshold above which power is cut
  1560. Low_Rpm_Pwr_Slope: DS 1 ; Sets the slope of power increase for low rpms
  1561. Prev_Comm_L: DS 1 ; Previous commutation timer3 timestamp (lo byte)
  1562. Prev_Comm_H: DS 1 ; Previous commutation timer3 timestamp (hi byte)
  1563. Comm_Period4x_L: DS 1 ; Timer3 counts between the last 4 commutations (lo byte)
  1564. Comm_Period4x_H: DS 1 ; Timer3 counts between the last 4 commutations (hi byte)
  1565. Comm_Phase: DS 1 ; Current commutation phase
  1566. Comparator_Read_Cnt: DS 1 ; Number of comparator reads done
  1567. Gov_Target_L: DS 1 ; Governor target (lo byte)
  1568. Gov_Target_H: DS 1 ; Governor target (hi byte)
  1569. Gov_Integral_L: DS 1 ; Governor integral error (lo byte)
  1570. Gov_Integral_H: DS 1 ; Governor integral error (hi byte)
  1571. Gov_Integral_X: DS 1 ; Governor integral error (ex byte)
  1572. Gov_Proportional_L: DS 1 ; Governor proportional error (lo byte)
  1573. Gov_Proportional_H: DS 1 ; Governor proportional error (hi byte)
  1574. Gov_Prop_Pwm: DS 1 ; Governor calculated new pwm based upon proportional error
  1575. Gov_Arm_Target: DS 1 ; Governor arm target value
  1576. Gov_Active: DS 1 ; Governor active (enabled when speed is above minimum)
  1577. Wt_Advance_L: DS 1 ; Timer3 counts for commutation advance timing (lo byte)
  1578. Wt_Advance_H: DS 1 ; Timer3 counts for commutation advance timing (hi byte)
  1579. Wt_Zc_Scan_L: DS 1 ; Timer3 counts from commutation to zero cross scan (lo byte)
  1580. Wt_Zc_Scan_H: DS 1 ; Timer3 counts from commutation to zero cross scan (hi byte)
  1581. Wt_Zc_Timeout_L: DS 1 ; Timer3 counts for zero cross scan timeout (lo byte)
  1582. Wt_Zc_Timeout_H: DS 1 ; Timer3 counts for zero cross scan timeout (hi byte)
  1583. Wt_Comm_L: DS 1 ; Timer3 counts from zero cross to commutation (lo byte)
  1584. Wt_Comm_H: DS 1 ; Timer3 counts from zero cross to commutation (hi byte)
  1585. Next_Wt_L: DS 1 ; Timer3 counts for next wait period (lo byte)
  1586. Next_Wt_H: DS 1 ; Timer3 counts for next wait period (hi byte)
  1587. Rcp_PrePrev_Edge_L: DS 1 ; RC pulse pre previous edge pca timestamp (lo byte)
  1588. Rcp_PrePrev_Edge_H: DS 1 ; RC pulse pre previous edge pca timestamp (hi byte)
  1589. Rcp_Edge_L: DS 1 ; RC pulse edge pca timestamp (lo byte)
  1590. Rcp_Edge_H: DS 1 ; RC pulse edge pca timestamp (hi byte)
  1591. Rcp_Prev_Period_L: DS 1 ; RC pulse previous period (lo byte)
  1592. Rcp_Prev_Period_H: DS 1 ; RC pulse previous period (hi byte)
  1593. Rcp_Period_Diff_Accepted: DS 1 ; RC pulse period difference acceptable
  1594. New_Rcp: DS 1 ; New RC pulse value in pca counts
  1595. Prev_Rcp_Pwm_Freq: DS 1 ; Previous RC pulse pwm frequency (used during pwm frequency measurement)
  1596. Curr_Rcp_Pwm_Freq: DS 1 ; Current RC pulse pwm frequency (used during pwm frequency measurement)
  1597. Rcp_Stop_Cnt: DS 1 ; Counter for RC pulses below stop value
  1598. Auto_Bailout_Armed: DS 1 ; Set when auto rotation bailout is armed
  1599. Pwm_Limit: DS 1 ; Maximum allowed pwm
  1600. Pwm_Limit_Spoolup: DS 1 ; Maximum allowed pwm during spoolup
  1601. Pwm_Limit_Low_Rpm: DS 1 ; Maximum allowed pwm for low rpms
  1602. Pwm_Spoolup_Beg: DS 1 ; Pwm to begin main spoolup with
  1603. Pwm_Motor_Idle: DS 1 ; Motor idle speed pwm
  1604. Pwm_On_Cnt: DS 1 ; Pwm on event counter (used to increase pwm off time for low pwm)
  1605. Spoolup_Limit_Cnt: DS 1 ; Interrupt count for spoolup limit
  1606. Spoolup_Limit_Skip: DS 1 ; Interrupt skips for spoolup limit increment (1=no skips, 2=skip one etc)
  1607. Main_Spoolup_Time_3x: DS 1 ; Main spoolup time x3
  1608. Main_Spoolup_Time_10x: DS 1 ; Main spoolup time x10
  1609. Main_Spoolup_Time_15x: DS 1 ; Main spoolup time x15
  1610. Lipo_Adc_Reference_L: DS 1 ; Voltage reference adc value (lo byte)
  1611. Lipo_Adc_Reference_H: DS 1 ; Voltage reference adc value (hi byte)
  1612. Lipo_Adc_Limit_L: DS 1 ; Low voltage limit adc value (lo byte)
  1613. Lipo_Adc_Limit_H: DS 1 ; Low voltage limit adc value (hi byte)
  1614. Adc_Conversion_Cnt: DS 1 ; Adc conversion counter
  1615. Current_Average_Temp: DS 1 ; Current average temperature (lo byte ADC reading, assuming hi byte is 1)
  1616. Ppm_Throttle_Gain: DS 1 ; Gain to be applied to RCP value for PPM input
  1617. Beep_Strength: DS 1 ; Strength of beeps
  1618. Tx_Pgm_Func_No: DS 1 ; Function number when doing programming by tx
  1619. Tx_Pgm_Paraval_No: DS 1 ; Parameter value number when doing programming by tx
  1620. Tx_Pgm_Beep_No: DS 1 ; Beep number when doing programming by tx
  1621. Skip_T2_Int: DS 1 ; Set for 50MHz MCUs when timer 2 interrupt shall be ignored
  1622. Skip_T2h_Int: DS 1 ; Set for 50MHz MCUs when timer 2 high interrupt shall be ignored
  1623. Timer0_Overflow_Value: DS 1 ; Remaining timer 0 wait time used with 50MHz MCUs
  1624. Clock_Set_At_50MHz: DS 1 ; Variable set if 50MHz MCUs run at 50MHz
  1625. ; Indirect addressing data segment. The variables below must be in this sequence
  1626. ISEG AT 080h
  1627. Pgm_Gov_P_Gain: DS 1 ; Programmed governor P gain
  1628. Pgm_Gov_I_Gain: DS 1 ; Programmed governor I gain
  1629. Pgm_Gov_Mode: DS 1 ; Programmed governor mode
  1630. Pgm_Low_Voltage_Lim: DS 1 ; Programmed low voltage limit
  1631. Pgm_Motor_Gain: DS 1 ; Programmed motor gain
  1632. Pgm_Motor_Idle: DS 1 ; Programmed motor idle speed
  1633. Pgm_Startup_Pwr: DS 1 ; Programmed startup power
  1634. Pgm_Pwm_Freq: DS 1 ; Programmed pwm frequency
  1635. Pgm_Direction: DS 1 ; Programmed rotation direction
  1636. Pgm_Input_Pol: DS 1 ; Programmed input pwm polarity
  1637. Initialized_L_Dummy: DS 1 ; Place holder
  1638. Initialized_H_Dummy: DS 1 ; Place holder
  1639. Pgm_Enable_TX_Program: DS 1 ; Programmed enable/disable value for TX programming
  1640. Pgm_Main_Rearm_Start: DS 1 ; Programmed enable/disable re-arming main every start
  1641. Pgm_Gov_Setup_Target: DS 1 ; Programmed main governor setup target
  1642. _Pgm_Startup_Rpm: DS 1 ; Programmed startup rpm (unused - place holder)
  1643. _Pgm_Startup_Accel: DS 1 ; Programmed startup acceleration (unused - place holder)
  1644. _Pgm_Volt_Comp: DS 1 ; Place holder
  1645. Pgm_Comm_Timing: DS 1 ; Programmed commutation timing
  1646. _Pgm_Damping_Force: DS 1 ; Programmed damping force (unused - place holder)
  1647. Pgm_Gov_Range: DS 1 ; Programmed governor range
  1648. _Pgm_Startup_Method: DS 1 ; Programmed startup method (unused - place holder)
  1649. Pgm_Ppm_Min_Throttle: DS 1 ; Programmed throttle minimum
  1650. Pgm_Ppm_Max_Throttle: DS 1 ; Programmed throttle maximum
  1651. Pgm_Beep_Strength: DS 1 ; Programmed beep strength
  1652. Pgm_Beacon_Strength: DS 1 ; Programmed beacon strength
  1653. Pgm_Beacon_Delay: DS 1 ; Programmed beacon delay
  1654. _Pgm_Throttle_Rate: DS 1 ; Programmed throttle rate (unused - place holder)
  1655. Pgm_Demag_Comp: DS 1 ; Programmed demag compensation
  1656. Pgm_BEC_Voltage_High: DS 1 ; Programmed BEC voltage
  1657. Pgm_Ppm_Center_Throttle: DS 1 ; Programmed throttle center (in bidirectional mode)
  1658. Pgm_Main_Spoolup_Time: DS 1 ; Programmed main spoolup time
  1659. Pgm_Enable_Temp_Prot: DS 1 ; Programmed temperature protection enable
  1660. ; The sequence of the variables below is no longer of importance
  1661. Pgm_Gov_P_Gain_Decoded: DS 1 ; Programmed governor decoded P gain
  1662. Pgm_Gov_I_Gain_Decoded: DS 1 ; Programmed governor decoded I gain
  1663. Pgm_Startup_Pwr_Decoded: DS 1 ; Programmed startup power decoded
  1664. ; Indirect addressing data segment
  1665. ISEG AT 0D0h
  1666. Tag_Temporary_Storage: DS 48 ; Temporary storage for tags when updating "Eeprom"
  1667. ;**** **** **** **** ****
  1668. CSEG AT 1A00h ; "Eeprom" segment
  1669. EEPROM_FW_MAIN_REVISION EQU 13 ; Main revision of the firmware
  1670. EEPROM_FW_SUB_REVISION EQU 2 ; Sub revision of the firmware
  1671. EEPROM_LAYOUT_REVISION EQU 19 ; Revision of the EEPROM layout
  1672. Eep_FW_Main_Revision: DB EEPROM_FW_MAIN_REVISION ; EEPROM firmware main revision number
  1673. Eep_FW_Sub_Revision: DB EEPROM_FW_SUB_REVISION ; EEPROM firmware sub revision number
  1674. Eep_Layout_Revision: DB EEPROM_LAYOUT_REVISION ; EEPROM layout revision number
  1675. IF MODE == 0
  1676. Eep_Pgm_Gov_P_Gain: DB DEFAULT_PGM_MAIN_P_GAIN ; EEPROM copy of programmed governor P gain
  1677. Eep_Pgm_Gov_I_Gain: DB DEFAULT_PGM_MAIN_I_GAIN ; EEPROM copy of programmed governor I gain
  1678. Eep_Pgm_Gov_Mode: DB DEFAULT_PGM_MAIN_GOVERNOR_MODE ; EEPROM copy of programmed governor mode
  1679. Eep_Pgm_Low_Voltage_Lim: DB DEFAULT_PGM_MAIN_LOW_VOLTAGE_LIM ; EEPROM copy of programmed low voltage limit
  1680. _Eep_Pgm_Motor_Gain: DB 0FFh
  1681. _Eep_Pgm_Motor_Idle: DB 0FFh
  1682. Eep_Pgm_Startup_Pwr: DB DEFAULT_PGM_MAIN_STARTUP_PWR ; EEPROM copy of programmed startup power
  1683. Eep_Pgm_Pwm_Freq: DB DEFAULT_PGM_MAIN_PWM_FREQ ; EEPROM copy of programmed pwm frequency
  1684. Eep_Pgm_Direction: DB DEFAULT_PGM_MAIN_DIRECTION ; EEPROM copy of programmed rotation direction
  1685. Eep_Pgm_Input_Pol: DB DEFAULT_PGM_MAIN_RCP_PWM_POL ; EEPROM copy of programmed input polarity
  1686. Eep_Initialized_L: DB 0A5h ; EEPROM initialized signature low byte
  1687. Eep_Initialized_H: DB 05Ah ; EEPROM initialized signature high byte
  1688. Eep_Enable_TX_Program: DB DEFAULT_PGM_ENABLE_TX_PROGRAM ; EEPROM TX programming enable
  1689. Eep_Main_Rearm_Start: DB DEFAULT_PGM_MAIN_REARM_START ; EEPROM re-arming main enable
  1690. Eep_Pgm_Gov_Setup_Target: DB DEFAULT_PGM_MAIN_GOV_SETUP_TARGET ; EEPROM main governor setup target
  1691. _Eep_Pgm_Startup_Rpm: DB 0FFh
  1692. _Eep_Pgm_Startup_Accel: DB 0FFh
  1693. _Eep_Pgm_Volt_Comp: DB 0FFh
  1694. Eep_Pgm_Comm_Timing: DB DEFAULT_PGM_MAIN_COMM_TIMING ; EEPROM copy of programmed commutation timing
  1695. _Eep_Pgm_Damping_Force: DB 0FFh
  1696. Eep_Pgm_Gov_Range: DB DEFAULT_PGM_MAIN_GOVERNOR_RANGE ; EEPROM copy of programmed governor range
  1697. _Eep_Pgm_Startup_Method: DB 0FFh
  1698. Eep_Pgm_Ppm_Min_Throttle: DB DEFAULT_PGM_PPM_MIN_THROTTLE ; EEPROM copy of programmed minimum throttle (final value is 4x+1000=1148)
  1699. Eep_Pgm_Ppm_Max_Throttle: DB DEFAULT_PGM_PPM_MAX_THROTTLE ; EEPROM copy of programmed minimum throttle (final value is 4x+1000=1832)
  1700. Eep_Pgm_Beep_Strength: DB DEFAULT_PGM_MAIN_BEEP_STRENGTH ; EEPROM copy of programmed beep strength
  1701. Eep_Pgm_Beacon_Strength: DB DEFAULT_PGM_MAIN_BEACON_STRENGTH ; EEPROM copy of programmed beacon strength
  1702. Eep_Pgm_Beacon_Delay: DB DEFAULT_PGM_MAIN_BEACON_DELAY ; EEPROM copy of programmed beacon delay
  1703. _Eep_Pgm_Throttle_Rate: DB 0FFh
  1704. Eep_Pgm_Demag_Comp: DB DEFAULT_PGM_MAIN_DEMAG_COMP ; EEPROM copy of programmed demag compensation
  1705. Eep_Pgm_BEC_Voltage_High: DB DEFAULT_PGM_BEC_VOLTAGE_HIGH ; EEPROM copy of programmed BEC voltage
  1706. _Eep_Pgm_Ppm_Center_Throttle: DB 0FFh ; EEPROM copy of programmed center throttle (final value is 4x+1000=1488)
  1707. Eep_Pgm_Main_Spoolup_Time: DB DEFAULT_PGM_MAIN_SPOOLUP_TIME ; EEPROM copy of programmed main spoolup time
  1708. Eep_Pgm_Temp_Prot_Enable: DB DEFAULT_PGM_ENABLE_TEMP_PROT ; EEPROM copy of programmed temperature protection enable
  1709. ENDIF
  1710. IF MODE == 1
  1711. _Eep_Pgm_Gov_P_Gain: DB 0FFh
  1712. _Eep_Pgm_Gov_I_Gain: DB 0FFh
  1713. _Eep_Pgm_Gov_Mode: DB 0FFh
  1714. _Eep_Pgm_Low_Voltage_Lim: DB 0FFh
  1715. Eep_Pgm_Motor_Gain: DB DEFAULT_PGM_TAIL_GAIN ; EEPROM copy of programmed tail gain
  1716. Eep_Pgm_Motor_Idle: DB DEFAULT_PGM_TAIL_IDLE_SPEED ; EEPROM copy of programmed tail idle speed
  1717. Eep_Pgm_Startup_Pwr: DB DEFAULT_PGM_TAIL_STARTUP_PWR ; EEPROM copy of programmed startup power
  1718. Eep_Pgm_Pwm_Freq: DB DEFAULT_PGM_TAIL_PWM_FREQ ; EEPROM copy of programmed pwm frequency
  1719. Eep_Pgm_Direction: DB DEFAULT_PGM_TAIL_DIRECTION ; EEPROM copy of programmed rotation direction
  1720. Eep_Pgm_Input_Pol: DB DEFAULT_PGM_TAIL_RCP_PWM_POL ; EEPROM copy of programmed input polarity
  1721. Eep_Initialized_L: DB 05Ah ; EEPROM initialized signature low byte
  1722. Eep_Initialized_H: DB 0A5h ; EEPROM initialized signature high byte
  1723. Eep_Enable_TX_Program: DB DEFAULT_PGM_ENABLE_TX_PROGRAM ; EEPROM TX programming enable
  1724. _Eep_Main_Rearm_Start: DB 0FFh
  1725. _Eep_Pgm_Gov_Setup_Target: DB 0FFh
  1726. _Eep_Pgm_Startup_Rpm: DB 0FFh
  1727. _Eep_Pgm_Startup_Accel: DB 0FFh
  1728. _Eep_Pgm_Volt_Comp: DB 0FFh
  1729. Eep_Pgm_Comm_Timing: DB DEFAULT_PGM_TAIL_COMM_TIMING ; EEPROM copy of programmed commutation timing
  1730. _Eep_Pgm_Damping_Force: DB 0FFh
  1731. _Eep_Pgm_Gov_Range: DB 0FFh
  1732. _Eep_Pgm_Startup_Method: DB 0FFh
  1733. Eep_Pgm_Ppm_Min_Throttle: DB DEFAULT_PGM_PPM_MIN_THROTTLE ; EEPROM copy of programmed minimum throttle (final value is 4x+1000=1148)
  1734. Eep_Pgm_Ppm_Max_Throttle: DB DEFAULT_PGM_PPM_MAX_THROTTLE ; EEPROM copy of programmed minimum throttle (final value is 4x+1000=1832)
  1735. Eep_Pgm_Beep_Strength: DB DEFAULT_PGM_TAIL_BEEP_STRENGTH ; EEPROM copy of programmed beep strength
  1736. Eep_Pgm_Beacon_Strength: DB DEFAULT_PGM_TAIL_BEACON_STRENGTH ; EEPROM copy of programmed beacon strength
  1737. Eep_Pgm_Beacon_Delay: DB DEFAULT_PGM_TAIL_BEACON_DELAY ; EEPROM copy of programmed beacon delay
  1738. _Eep_Pgm_Throttle_Rate: DB 0FFh
  1739. Eep_Pgm_Demag_Comp: DB DEFAULT_PGM_TAIL_DEMAG_COMP ; EEPROM copy of programmed demag compensation
  1740. Eep_Pgm_BEC_Voltage_High: DB DEFAULT_PGM_BEC_VOLTAGE_HIGH ; EEPROM copy of programmed BEC voltage
  1741. Eep_Pgm_Ppm_Center_Throttle: DB DEFAULT_PGM_PPM_CENTER_THROTTLE ; EEPROM copy of programmed center throttle (final value is 4x+1000=1488)
  1742. _Eep_Pgm_Main_Spoolup_Time: DB 0FFh
  1743. Eep_Pgm_Temp_Prot_Enable: DB DEFAULT_PGM_ENABLE_TEMP_PROT ; EEPROM copy of programmed temperature protection enable
  1744. ENDIF
  1745. IF MODE == 2
  1746. Eep_Pgm_Gov_P_Gain: DB DEFAULT_PGM_MULTI_P_GAIN ; EEPROM copy of programmed closed loop P gain
  1747. Eep_Pgm_Gov_I_Gain: DB DEFAULT_PGM_MULTI_I_GAIN ; EEPROM copy of programmed closed loop I gain
  1748. Eep_Pgm_Gov_Mode: DB DEFAULT_PGM_MULTI_GOVERNOR_MODE ; EEPROM copy of programmed closed loop mode
  1749. Eep_Pgm_Low_Voltage_Lim: DB DEFAULT_PGM_MULTI_LOW_VOLTAGE_LIM ; EEPROM copy of programmed low voltage limit
  1750. Eep_Pgm_Motor_Gain: DB DEFAULT_PGM_MULTI_GAIN ; EEPROM copy of programmed tail gain
  1751. _Eep_Pgm_Motor_Idle: DB 0FFh ; EEPROM copy of programmed tail idle speed
  1752. Eep_Pgm_Startup_Pwr: DB DEFAULT_PGM_MULTI_STARTUP_PWR ; EEPROM copy of programmed startup power
  1753. Eep_Pgm_Pwm_Freq: DB DEFAULT_PGM_MULTI_PWM_FREQ ; EEPROM copy of programmed pwm frequency
  1754. Eep_Pgm_Direction: DB DEFAULT_PGM_MULTI_DIRECTION ; EEPROM copy of programmed rotation direction
  1755. Eep_Pgm_Input_Pol: DB DEFAULT_PGM_MULTI_RCP_PWM_POL ; EEPROM copy of programmed input polarity
  1756. Eep_Initialized_L: DB 055h ; EEPROM initialized signature low byte
  1757. Eep_Initialized_H: DB 0AAh ; EEPROM initialized signature high byte
  1758. Eep_Enable_TX_Program: DB DEFAULT_PGM_ENABLE_TX_PROGRAM ; EEPROM TX programming enable
  1759. _Eep_Main_Rearm_Start: DB 0FFh
  1760. _Eep_Pgm_Gov_Setup_Target: DB 0FFh
  1761. _Eep_Pgm_Startup_Rpm: DB 0FFh
  1762. _Eep_Pgm_Startup_Accel: DB 0FFh
  1763. _Eep_Pgm_Volt_Comp: DB 0FFh
  1764. Eep_Pgm_Comm_Timing: DB DEFAULT_PGM_MULTI_COMM_TIMING ; EEPROM copy of programmed commutation timing
  1765. _Eep_Pgm_Damping_Force: DB 0FFh
  1766. _Eep_Pgm_Gov_Range: DB 0FFh
  1767. _Eep_Pgm_Startup_Method: DB 0FFh
  1768. Eep_Pgm_Ppm_Min_Throttle: DB DEFAULT_PGM_PPM_MIN_THROTTLE ; EEPROM copy of programmed minimum throttle (final value is 4x+1000=1148)
  1769. Eep_Pgm_Ppm_Max_Throttle: DB DEFAULT_PGM_PPM_MAX_THROTTLE ; EEPROM copy of programmed minimum throttle (final value is 4x+1000=1832)
  1770. Eep_Pgm_Beep_Strength: DB DEFAULT_PGM_MULTI_BEEP_STRENGTH ; EEPROM copy of programmed beep strength
  1771. Eep_Pgm_Beacon_Strength: DB DEFAULT_PGM_MULTI_BEACON_STRENGTH ; EEPROM copy of programmed beacon strength
  1772. Eep_Pgm_Beacon_Delay: DB DEFAULT_PGM_MULTI_BEACON_DELAY ; EEPROM copy of programmed beacon delay
  1773. _Eep_Pgm_Throttle_Rate: DB 0FFh
  1774. Eep_Pgm_Demag_Comp: DB DEFAULT_PGM_MULTI_DEMAG_COMP ; EEPROM copy of programmed demag compensation
  1775. Eep_Pgm_BEC_Voltage_High: DB DEFAULT_PGM_BEC_VOLTAGE_HIGH ; EEPROM copy of programmed BEC voltage
  1776. Eep_Pgm_Ppm_Center_Throttle: DB DEFAULT_PGM_PPM_CENTER_THROTTLE ; EEPROM copy of programmed center throttle (final value is 4x+1000=1488)
  1777. _Eep_Pgm_Main_Spoolup_Time: DB 0FFh
  1778. Eep_Pgm_Temp_Prot_Enable: DB DEFAULT_PGM_ENABLE_TEMP_PROT ; EEPROM copy of programmed temperature protection enable
  1779. ENDIF
  1780. Eep_Dummy: DB 0FFh ; EEPROM address for safety reason
  1781. CSEG AT 1A60h
  1782. Eep_Name: DB " " ; Name tag (16 Bytes)
  1783. ;**** **** **** **** ****
  1784. Interrupt_Table_Definition ; SiLabs interrupts
  1785. CSEG AT 80h ; Code segment after interrupt vectors
  1786. ;**** **** **** **** ****
  1787. ; Table definitions
  1788. GOV_GAIN_TABLE: DB 02h, 03h, 04h, 06h, 08h, 0Ch, 10h, 18h, 20h, 30h, 40h, 60h, 80h
  1789. STARTUP_POWER_TABLE: DB 04h, 06h, 08h, 0Ch, 10h, 18h, 20h, 30h, 40h, 60h, 80h, 0A0h, 0C0h
  1790. IF MODE == 0
  1791. IF DAMPED_MODE_ENABLE == 1
  1792. TX_PGM_PARAMS_MAIN: DB 13, 13, 4, 3, 6, 13, 5, 3, 3, 2, 2
  1793. ENDIF
  1794. IF DAMPED_MODE_ENABLE == 0
  1795. TX_PGM_PARAMS_MAIN: DB 13, 13, 4, 3, 6, 13, 5, 2, 3, 2, 2
  1796. ENDIF
  1797. ENDIF
  1798. IF MODE == 1
  1799. IF DAMPED_MODE_ENABLE == 1
  1800. TX_PGM_PARAMS_TAIL: DB 5, 5, 13, 5, 3, 3, 3, 2
  1801. ENDIF
  1802. IF DAMPED_MODE_ENABLE == 0
  1803. TX_PGM_PARAMS_TAIL: DB 5, 5, 13, 5, 2, 3, 3, 2
  1804. ENDIF
  1805. ENDIF
  1806. IF MODE == 2
  1807. IF DAMPED_MODE_ENABLE == 1
  1808. TX_PGM_PARAMS_MULTI: DB 13, 13, 4, 5, 6, 13, 5, 3, 3, 3, 2
  1809. ENDIF
  1810. IF DAMPED_MODE_ENABLE == 0
  1811. TX_PGM_PARAMS_MULTI: DB 13, 13, 4, 5, 6, 13, 5, 2, 3, 3, 2
  1812. ENDIF
  1813. ENDIF
  1814. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  1815. ;
  1816. ; Timer0 interrupt routine
  1817. ;
  1818. ; Assumptions: DPTR register must be set to desired pwm_nfet_on label
  1819. ; Requirements: Temp variables can NOT be used since PSW.3 is not set
  1820. ;
  1821. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  1822. t0_int: ; Used for pwm control
  1823. IF MCU_50MHZ == 1
  1824. ; Check overflow flag
  1825. jnb Flags0.PWM_TIMER0_OVERFLOW, t0_int_start; Execute this interrupt
  1826. clr Flags0.PWM_TIMER0_OVERFLOW
  1827. mov TL0, Timer0_Overflow_Value ; Set timer
  1828. reti
  1829. t0_int_start:
  1830. ENDIF
  1831. clr EA ; Disable all interrupts
  1832. push PSW ; Preserve registers through interrupt
  1833. push ACC
  1834. ; Check if pwm is on
  1835. jb Flags0.PWM_ON, t0_int_pwm_off ; Is pwm on?
  1836. ; Do not execute pwm when stopped
  1837. jb Flags1.MOTOR_SPINNING, ($+5)
  1838. ajmp t0_int_pwm_on_exit
  1839. ; Do not execute pwm on during demag recovery
  1840. jnb Flags0.DEMAG_CUT_POWER, ($+5)
  1841. ajmp t0_int_pwm_on_exit_pfets_off
  1842. ; Pwm on cycle.
  1843. IF MODE == 1 ; Tail
  1844. jnb Current_Pwm_Limited.7, t0_int_pwm_on_low_pwm ; Jump for low pwm (<50%)
  1845. ENDIF
  1846. t0_int_pwm_on_execute:
  1847. clr A
  1848. jmp @A+DPTR ; Jump to pwm on routines. DPTR should be set to one of the pwm_nfet_on labels
  1849. IF MODE == 1 ; Tail
  1850. t0_int_pwm_on_low_pwm:
  1851. ; Skip pwm on cycles for very low pwm
  1852. inc Pwm_On_Cnt ; Increment event counter
  1853. clr C
  1854. mov A, #5 ; Only skip for very low pwm
  1855. subb A, Current_Pwm_Limited ; Check skipping shall be done (for low pwm only)
  1856. jc t0_int_pwm_on_execute
  1857. subb A, Pwm_On_Cnt ; Check if on cycle is to be skipped
  1858. jc t0_int_pwm_on_execute
  1859. jb Flags1.STARTUP_PHASE, t0_int_pwm_on_execute
  1860. IF MCU_50MHZ == 0
  1861. mov TL0, #120 ; Write start point for timer
  1862. mov A, Current_Pwm_Limited
  1863. jnz t0_int_pwm_on_low_pwm_done
  1864. mov TL0, #0 ; Write start point for timer (long time for zero pwm)
  1865. ELSE
  1866. mov TL0, #0
  1867. mov TH1, #0
  1868. mov A, Current_Pwm_Limited
  1869. jnz t0_int_pwm_on_low_pwm_done
  1870. mov TL0, #0
  1871. mov TH1, #0
  1872. setb Flags0.PWM_TIMER0_OVERFLOW
  1873. mov Timer0_Overflow_Value, #0
  1874. ENDIF
  1875. t0_int_pwm_on_low_pwm_done:
  1876. jmp t0_int_pwm_on_exit_no_timer_update
  1877. ENDIF
  1878. t0_int_pwm_off:
  1879. ; Pwm off cycle
  1880. IF MCU_50MHZ == 0
  1881. mov TL0, Current_Pwm_Limited ; Load new timer setting
  1882. ELSE
  1883. clr C
  1884. mov A, Current_Pwm_Limited
  1885. rlc A
  1886. jc t0_int_pwm_off_set_timer
  1887. mov TL0, #0
  1888. setb Flags0.PWM_TIMER0_OVERFLOW
  1889. mov Timer0_Overflow_Value, A
  1890. ajmp t0_int_pwm_off_timer_set
  1891. t0_int_pwm_off_set_timer:
  1892. mov TL0, A
  1893. t0_int_pwm_off_timer_set:
  1894. ENDIF
  1895. ; Clear pwm on flag
  1896. clr Flags0.PWM_ON
  1897. ; Set full PWM (on all the time) if current PWM near max. This will give full power, but at the cost of a small "jump" in power
  1898. mov A, Current_Pwm_Limited ; Load current pwm
  1899. cpl A ; Full pwm?
  1900. jnz ($+4) ; No - branch
  1901. ajmp t0_int_pwm_off_fullpower_exit ; Yes - exit
  1902. ; Do not execute pwm when stopped
  1903. jb Flags1.MOTOR_SPINNING, ($+5)
  1904. ajmp t0_int_pwm_off_exit_nfets_off
  1905. IF DAMPED_MODE_ENABLE == 1
  1906. ; If damped operation, set pFETs on in pwm_off
  1907. jb Flags2.PGM_PWMOFF_DAMPED, t0_int_pwm_off_damped ; Damped operation?
  1908. ENDIF
  1909. ; Separate exit commands here for minimum delay
  1910. mov TL1, #0 ; Reset timer1
  1911. IF MCU_50MHZ == 1
  1912. mov TH1, #0
  1913. ENDIF
  1914. pop ACC ; Restore preserved registers
  1915. pop PSW
  1916. All_nFETs_Off ; Switch off all nfets
  1917. setb EA ; Enable all interrupts
  1918. reti
  1919. t0_int_pwm_off_damped:
  1920. All_nFETs_Off ; Switch off all nfets
  1921. mov A, #PFETON_DELAY
  1922. djnz ACC, $
  1923. mov A, Comm_Phase ; Turn on pfets according to commutation phase
  1924. dec A
  1925. jb ACC.2, t0_int_pwm_off_comm_5_6
  1926. jb ACC.1, t0_int_pwm_off_comm_3_4
  1927. CpFET_On ; Comm phase 1 or 2 - turn on C
  1928. jmp t0_int_pwm_off_exit
  1929. t0_int_pwm_off_comm_3_4:
  1930. BpFET_On ; Comm phase 3 or 4 - turn on B
  1931. jmp t0_int_pwm_off_exit
  1932. t0_int_pwm_off_comm_5_6:
  1933. ApFET_On ; Comm phase 5 or 6 - turn on A
  1934. jmp t0_int_pwm_off_exit
  1935. t0_int_pwm_off_exit_nfets_off: ; Exit from pwm off cycle
  1936. mov TL1, #0 ; Reset timer1
  1937. IF MCU_50MHZ == 1
  1938. mov TH1, #0
  1939. ENDIF
  1940. pop ACC ; Restore preserved registers
  1941. pop PSW
  1942. All_nFETs_Off ; Switch off all nfets
  1943. setb EA ; Enable all interrupts
  1944. reti
  1945. t0_int_pwm_off_exit:
  1946. mov TL1, #0 ; Reset timer1
  1947. IF MCU_50MHZ == 1
  1948. mov TH1, #0
  1949. ENDIF
  1950. t0_int_pwm_off_fullpower_exit:
  1951. pop ACC ; Restore preserved registers
  1952. pop PSW
  1953. setb EA ; Enable all interrupts
  1954. reti
  1955. pwm_nofet_on: ; Dummy pwm on cycle
  1956. ajmp t0_int_pwm_on_exit
  1957. pwm_afet_on: ; Pwm on cycle afet on (bfet off)
  1958. AnFET_on
  1959. BnFET_off
  1960. ajmp t0_int_pwm_on_exit
  1961. pwm_bfet_on: ; Pwm on cycle bfet on (cfet off)
  1962. BnFET_on
  1963. CnFET_off
  1964. ajmp t0_int_pwm_on_exit
  1965. pwm_cfet_on: ; Pwm on cycle cfet on (afet off)
  1966. CnFET_on
  1967. AnFET_off
  1968. ajmp t0_int_pwm_on_exit
  1969. pwm_anfet_bpfet_on: ; Pwm on cycle anfet on (bnfet off) and bpfet on (used in damped state 6)
  1970. ; Delay from pFETs are turned off (only in damped mode) until nFET is turned on (pFETs are slow)
  1971. ApFET_off
  1972. CpFET_off
  1973. mov A, #NFETON_DELAY ; Set full delay
  1974. djnz ACC, $
  1975. AnFET_on ; Switch nFETs
  1976. BnFET_off
  1977. ajmp t0_int_pwm_on_exit
  1978. pwm_anfet_cpfet_on: ; Pwm on cycle anfet on (bnfet off) and cpfet on (used in damped state 5)
  1979. ; Delay from pFETs are turned off (only in damped mode) until nFET is turned on (pFETs are slow)
  1980. ApFET_off
  1981. BpFET_off
  1982. mov A, #NFETON_DELAY ; Set full delay
  1983. djnz ACC, $
  1984. AnFET_on ; Switch nFETs
  1985. BnFET_off
  1986. ajmp t0_int_pwm_on_exit
  1987. pwm_bnfet_cpfet_on: ; Pwm on cycle bnfet on (cnfet off) and cpfet on (used in damped state 4)
  1988. ; Delay from pFETs are turned off (only in damped mode) until nFET is turned on (pFETs are slow)
  1989. BpFET_off
  1990. ApFET_off
  1991. mov A, #NFETON_DELAY ; Set full delay
  1992. djnz ACC, $
  1993. BnFET_on ; Switch nFETs
  1994. CnFET_off
  1995. ajmp t0_int_pwm_on_exit
  1996. pwm_bnfet_apfet_on: ; Pwm on cycle bnfet on (cnfet off) and apfet on (used in damped state 3)
  1997. ; Delay from pFETs are turned off (only in damped mode) until nFET is turned on (pFETs are slow)
  1998. BpFET_off
  1999. CpFET_off
  2000. mov A, #NFETON_DELAY ; Set full delay
  2001. djnz ACC, $
  2002. BnFET_on ; Switch nFETs
  2003. CnFET_off
  2004. ajmp t0_int_pwm_on_exit
  2005. pwm_cnfet_apfet_on: ; Pwm on cycle cnfet on (anfet off) and apfet on (used in damped state 2)
  2006. ; Delay from pFETs are turned off (only in damped mode) until nFET is turned on (pFETs are slow)
  2007. CpFET_off
  2008. BpFET_off
  2009. mov A, #NFETON_DELAY ; Set full delay
  2010. djnz ACC, $
  2011. CnFET_on ; Switch nFETs
  2012. AnFET_off
  2013. ajmp t0_int_pwm_on_exit
  2014. pwm_cnfet_bpfet_on: ; Pwm on cycle cnfet on (anfet off) and bpfet on (used in damped state 1)
  2015. ; Delay from pFETs are turned off (only in damped mode) until nFET is turned on (pFETs are slow)
  2016. CpFET_off
  2017. ApFET_off
  2018. mov A, #NFETON_DELAY ; Set full delay
  2019. djnz ACC, $
  2020. CnFET_on ; Switch nFETs
  2021. AnFET_off
  2022. ajmp t0_int_pwm_on_exit
  2023. t0_int_pwm_on_exit_pfets_off:
  2024. jnb Flags2.PGM_PWMOFF_DAMPED, t0_int_pwm_on_exit ; If not damped operation - branch
  2025. mov A, Comm_Phase ; Turn off pfets according to commutation phase
  2026. jb ACC.2, t0_int_pfets_off_comm_4_5_6
  2027. jb ACC.1, t0_int_pfets_off_comm_2_3
  2028. t0_int_pfets_off_comm_1_6:
  2029. ApFET_Off ; Comm phase 1 and 6 - turn off A and C
  2030. CpFET_Off
  2031. jmp t0_int_pwm_on_exit
  2032. t0_int_pfets_off_comm_4_5_6:
  2033. jb ACC.1, t0_int_pfets_off_comm_1_6
  2034. ApFET_Off ; Comm phase 4 and 5 - turn off A and B
  2035. BpFET_Off
  2036. jmp t0_int_pwm_on_exit
  2037. t0_int_pfets_off_comm_2_3:
  2038. BpFET_Off ; Comm phase 2 and 3 - turn off B and C
  2039. CpFET_Off
  2040. t0_int_pwm_on_exit:
  2041. ; Set timer for coming on cycle length
  2042. mov A, Current_Pwm_Limited ; Load current pwm
  2043. cpl A ; cpl is 255-x
  2044. IF MCU_50MHZ == 0
  2045. mov TL0, A ; Write start point for timer
  2046. ELSE
  2047. clr C
  2048. rlc A
  2049. jc t0_int_pwm_on_set_timer
  2050. mov TL0, #0
  2051. setb Flags0.PWM_TIMER0_OVERFLOW
  2052. mov Timer0_Overflow_Value, A
  2053. ajmp t0_int_pwm_on_timer_set
  2054. t0_int_pwm_on_set_timer:
  2055. mov TL0, A
  2056. t0_int_pwm_on_timer_set:
  2057. ENDIF
  2058. ; Set other variables
  2059. mov TL1, #0 ; Reset timer1
  2060. IF MCU_50MHZ == 1
  2061. mov TH1, #0
  2062. ENDIF
  2063. IF MODE == 1 ; Tail
  2064. mov Pwm_On_Cnt, #0 ; Reset pwm on event counter
  2065. ENDIF
  2066. setb Flags0.PWM_ON ; Set pwm on flag
  2067. t0_int_pwm_on_exit_no_timer_update:
  2068. ; Exit interrupt
  2069. pop ACC ; Restore preserved registers
  2070. pop PSW
  2071. setb EA ; Enable all interrupts
  2072. reti
  2073. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  2074. ;
  2075. ; Timer2 interrupt routine
  2076. ;
  2077. ; No assumptions
  2078. ;
  2079. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  2080. t2_int: ; Happens every 128us for low byte and every 32ms for high byte
  2081. clr EA
  2082. clr ET2 ; Disable timer2 interrupts
  2083. anl EIE1, #0EFh ; Disable PCA0 interrupts
  2084. push PSW ; Preserve registers through interrupt
  2085. push ACC
  2086. setb PSW.3 ; Select register bank 1 for interrupt routines
  2087. setb EA
  2088. IF MCU_50MHZ == 1
  2089. mov A, Clock_Set_At_50MHz
  2090. jz t2_int_start
  2091. ; Check skip variable
  2092. mov A, Skip_T2_Int
  2093. jz t2_int_start ; Execute this interrupt
  2094. mov Skip_T2_Int, #0
  2095. ajmp t2_int_exit
  2096. t2_int_start:
  2097. mov Skip_T2_Int, #1 ; Skip next interrupt
  2098. ENDIF
  2099. ; Clear low byte interrupt flag
  2100. clr TF2L ; Clear interrupt flag
  2101. ; Check RC pulse timeout counter
  2102. mov A, Rcp_Timeout_Cnt ; RC pulse timeout count zero?
  2103. jz t2_int_pulses_absent ; Yes - pulses are absent
  2104. ; Decrement timeout counter (if PWM)
  2105. jb Flags2.RCP_PPM, t2_int_skip_start ; If flag is set (PPM) - branch
  2106. dec Rcp_Timeout_Cnt ; No - decrement
  2107. ajmp t2_int_skip_start
  2108. t2_int_pulses_absent:
  2109. ; Timeout counter has reached zero, pulses are absent
  2110. mov Temp1, #RCP_MIN ; RCP_MIN as default
  2111. mov Temp2, #RCP_MIN
  2112. Read_Rcp_Int ; Look at value of Rcp_In
  2113. jnb ACC.Rcp_In, ($+5) ; Is it high?
  2114. mov Temp1, #RCP_MAX ; Yes - set RCP_MAX
  2115. Rcp_Int_First ; Set interrupt trig to first again
  2116. Rcp_Clear_Int_Flag ; Clear interrupt flag
  2117. clr Flags2.RCP_EDGE_NO ; Set first edge flag
  2118. Read_Rcp_Int ; Look once more at value of Rcp_In
  2119. jnb ACC.Rcp_In, ($+5) ; Is it high?
  2120. mov Temp2, #RCP_MAX ; Yes - set RCP_MAX
  2121. clr C
  2122. mov A, Temp1
  2123. subb A, Temp2 ; Compare the two readings of Rcp_In
  2124. jnz t2_int_pulses_absent ; Go back if they are not equal
  2125. jnb Flags0.RCP_MEAS_PWM_FREQ, ($+6) ; Is measure RCP pwm frequency flag set?
  2126. mov Rcp_Timeout_Cnt, #RCP_TIMEOUT ; Yes - set timeout count to start value
  2127. jb Flags2.RCP_PPM, t2_int_ppm_timeout_set ; If flag is set (PPM) - branch
  2128. mov Rcp_Timeout_Cnt, #RCP_TIMEOUT ; For PWM, set timeout count to start value
  2129. t2_int_ppm_timeout_set:
  2130. mov New_Rcp, Temp1 ; Store new pulse length
  2131. setb Flags2.RCP_UPDATED ; Set updated flag
  2132. t2_int_skip_start:
  2133. ; Check RC pulse skip counter
  2134. mov A, Rcp_Skip_Cnt
  2135. jz t2_int_skip_end ; If RC pulse skip count is zero - end skipping RC pulse detection
  2136. ; Decrement skip counter (only if edge counter is zero)
  2137. dec Rcp_Skip_Cnt ; Decrement
  2138. ajmp t2_int_rcp_update_start
  2139. t2_int_skip_end:
  2140. jb Flags2.RCP_PPM, t2_int_rcp_update_start ; If flag is set (PPM) - branch
  2141. ; Skip counter has reached zero, start looking for RC pulses again
  2142. Rcp_Int_Enable ; Enable RC pulse interrupt
  2143. Rcp_Clear_Int_Flag ; Clear interrupt flag
  2144. t2_int_rcp_update_start:
  2145. ; Process updated RC pulse
  2146. jb Flags2.RCP_UPDATED, ($+5) ; Is there an updated RC pulse available?
  2147. ajmp t2_int_current_pwm_done ; No - update pwm limits and exit
  2148. mov Temp1, New_Rcp ; Load new pulse value
  2149. jb Flags0.RCP_MEAS_PWM_FREQ, ($+5) ; If measure RCP pwm frequency flag set - do not clear flag
  2150. clr Flags2.RCP_UPDATED ; Flag that pulse has been evaluated
  2151. ; Use a gain of 1.0625x for pwm input if not governor mode
  2152. jb Flags2.RCP_PPM, t2_int_pwm_min_run ; If flag is set (PPM) - branch
  2153. IF MODE == 0 ; Main - do not adjust gain
  2154. ajmp t2_int_pwm_min_run
  2155. ELSE
  2156. IF MODE == 2 ; Multi
  2157. mov Temp2, #Pgm_Gov_Mode ; Closed loop mode?
  2158. cjne @Temp2, #4, t2_int_pwm_min_run; Yes - branch
  2159. ENDIF
  2160. ; Limit the maximum value to avoid wrap when scaled to pwm range
  2161. clr C
  2162. mov A, Temp1
  2163. subb A, #240 ; 240 = (255/1.0625) Needs to be updated according to multiplication factor below
  2164. jc t2_int_rcp_update_mult
  2165. mov A, #240 ; Set requested pwm to max
  2166. mov Temp1, A
  2167. t2_int_rcp_update_mult:
  2168. ; Multiply by 1.0625 (optional adjustment gyro gain)
  2169. mov A, Temp1
  2170. swap A ; After this "0.0625"
  2171. anl A, #0Fh
  2172. add A, Temp1
  2173. mov Temp1, A
  2174. ; Adjust tail gain
  2175. mov Temp2, #Pgm_Motor_Gain
  2176. cjne @Temp2, #3, ($+5) ; Is gain 1?
  2177. ajmp t2_int_pwm_min_run ; Yes - skip adjustment
  2178. clr C
  2179. rrc A ; After this "0.5"
  2180. clr C
  2181. rrc A ; After this "0.25"
  2182. mov Bit_Access_Int, @Temp2 ; (Temp2 has #Pgm_Motor_Gain)
  2183. jb Bit_Access_Int.0, t2_int_rcp_gain_corr ; Branch if bit 0 in gain is set
  2184. clr C
  2185. rrc A ; After this "0.125"
  2186. t2_int_rcp_gain_corr:
  2187. jb Bit_Access_Int.2, t2_int_rcp_gain_pos ; Branch if bit 2 in gain is set
  2188. clr C
  2189. xch A, Temp1
  2190. subb A, Temp1 ; Apply negative correction
  2191. mov Temp1, A
  2192. ajmp t2_int_pwm_min_run
  2193. t2_int_rcp_gain_pos:
  2194. add A, Temp1 ; Apply positive correction
  2195. mov Temp1, A
  2196. jnc t2_int_pwm_min_run ; Above max?
  2197. mov A, #0FFh ; Yes - limit
  2198. mov Temp1, A
  2199. ENDIF
  2200. t2_int_pwm_min_run:
  2201. IF MODE == 1 ; Tail - limit minimum pwm
  2202. ; Limit minimum pwm
  2203. clr C
  2204. mov A, Temp1
  2205. subb A, Pwm_Motor_Idle ; Is requested pwm lower than minimum?
  2206. jnc t2_int_pwm_update ; No - branch
  2207. mov A, Pwm_Motor_Idle ; Yes - limit pwm to Pwm_Motor_Idle
  2208. mov Temp1, A
  2209. ENDIF
  2210. t2_int_pwm_update:
  2211. ; Update requested_pwm
  2212. mov Requested_Pwm, Temp1 ; Set requested pwm
  2213. ; Limit pwm during direct start
  2214. jnb Flags1.STARTUP_PHASE, t2_int_current_pwm_update
  2215. IF MODE == 2 ; Multi
  2216. mov A, Requested_Pwm
  2217. add A, #8 ; Add an extra power boost during start
  2218. mov Requested_Pwm, A
  2219. jnc ($+5)
  2220. mov Requested_Pwm, #0FFh
  2221. ENDIF
  2222. clr C
  2223. mov A, Requested_Pwm ; Limit pwm during direct start
  2224. subb A, Pwm_Limit
  2225. jc t2_int_current_pwm_update
  2226. mov Requested_Pwm, Pwm_Limit
  2227. t2_int_current_pwm_update:
  2228. IF MODE == 0 OR MODE == 2 ; Main or multi
  2229. mov Temp1, #Pgm_Gov_Mode ; Governor mode?
  2230. cjne @Temp1, #4, t2_int_pwm_exit ; Yes - branch
  2231. ENDIF
  2232. mov Current_Pwm, Requested_Pwm ; Set equal as default
  2233. t2_int_current_pwm_done:
  2234. IF MODE >= 1 ; Tail or multi
  2235. ; Set current_pwm_limited
  2236. mov Temp1, Current_Pwm ; Default not limited
  2237. clr C
  2238. mov A, Current_Pwm ; Check against limit
  2239. subb A, Pwm_Limit
  2240. jc ($+4) ; If current pwm below limit - branch
  2241. mov Temp1, Pwm_Limit ; Limit pwm
  2242. IF MODE == 2 ; Multi
  2243. ; Limit pwm for low rpms
  2244. clr C
  2245. mov A, Temp1 ; Check against limit
  2246. subb A, Pwm_Limit_Low_Rpm
  2247. jc ($+4) ; If current pwm below limit - branch
  2248. mov Temp1, Pwm_Limit_Low_Rpm ; Limit pwm
  2249. ENDIF
  2250. mov Current_Pwm_Limited, Temp1
  2251. ENDIF
  2252. t2_int_pwm_exit:
  2253. ; Set demag enabled if pwm is above limit
  2254. clr C
  2255. mov A, Current_Pwm_Limited
  2256. subb A, #40h ; Set if above 25%
  2257. jc ($+4)
  2258. setb Flags0.DEMAG_ENABLED
  2259. t2_int_exit:
  2260. ; Check if high byte flag is set
  2261. jb TF2H, t2h_int
  2262. pop ACC ; Restore preserved registers
  2263. pop PSW
  2264. clr PSW.3 ; Select register bank 0 for main program routines
  2265. orl EIE1, #10h ; Enable PCA0 interrupts
  2266. setb ET2 ; Enable timer2 interrupts
  2267. reti
  2268. t2h_int:
  2269. IF MCU_50MHZ == 1
  2270. mov A, Clock_Set_At_50MHz
  2271. jz t2h_int_start
  2272. ; Check skip variable
  2273. mov A, Skip_T2h_Int
  2274. jz t2h_int_start ; Execute this interrupt
  2275. mov Skip_T2h_Int, #0
  2276. ajmp t2h_int_exit
  2277. t2h_int_start:
  2278. mov Skip_T2h_Int, #1 ; Skip next interrupt
  2279. ENDIF
  2280. ; High byte interrupt (happens every 32ms)
  2281. clr TF2H ; Clear interrupt flag
  2282. mov Temp1, #GOV_SPOOLRATE ; Load governor spool rate
  2283. ; Check RC pulse timeout counter (used here for PPM only)
  2284. mov A, Rcp_Timeout_Cnt ; RC pulse timeout count zero?
  2285. jz t2h_int_rcp_stop_check ; Yes - do not decrement
  2286. ; Decrement timeout counter (if PPM)
  2287. jnb Flags2.RCP_PPM, t2h_int_rcp_stop_check ; If flag is not set (PWM) - branch
  2288. dec Rcp_Timeout_Cnt ; No flag set (PPM) - decrement
  2289. t2h_int_rcp_stop_check:
  2290. ; Check RC pulse against stop value
  2291. clr C
  2292. mov A, New_Rcp ; Load new pulse value
  2293. subb A, #RCP_STOP ; Check if pulse is below stop value
  2294. jc t2h_int_rcp_stop
  2295. ; RC pulse higher than stop value, reset stop counter
  2296. mov Rcp_Stop_Cnt, #0 ; Reset rcp stop counter
  2297. ajmp t2h_int_rcp_gov_pwm
  2298. t2h_int_rcp_stop:
  2299. ; RC pulse less than stop value
  2300. mov Auto_Bailout_Armed, #0 ; Disarm bailout
  2301. mov Spoolup_Limit_Cnt, #0
  2302. mov A, Rcp_Stop_Cnt ; Increment stop counter
  2303. add A, #1
  2304. mov Rcp_Stop_Cnt, A
  2305. jnc t2h_int_rcp_gov_pwm ; Branch if counter has not wrapped
  2306. mov Rcp_Stop_Cnt, #0FFh ; Set stop counter to max
  2307. t2h_int_rcp_gov_pwm:
  2308. IF MODE == 0 ; Main
  2309. ; Update governor variables
  2310. mov Temp2, #Pgm_Gov_Mode ; Governor target by arm mode?
  2311. cjne @Temp2, #2, t2h_int_rcp_gov_by_setup ; No - branch
  2312. mov A, Gov_Active ; Is governor active?
  2313. jz t2h_int_rcp_gov_by_tx ; No - branch (this ensures soft spoolup by tx)
  2314. clr C
  2315. mov A, Requested_Pwm
  2316. subb A, #50 ; Is requested pwm below 20%?
  2317. jc t2h_int_rcp_gov_by_tx ; Yes - branch (this enables a soft spooldown)
  2318. mov Requested_Pwm, Gov_Arm_Target ; Yes - load arm target
  2319. t2h_int_rcp_gov_by_setup:
  2320. mov Temp2, #Pgm_Gov_Mode ; Governor target by setup mode?
  2321. cjne @Temp2, #3, t2h_int_rcp_gov_by_tx ; No - branch
  2322. mov A, Gov_Active ; Is governor active?
  2323. jz t2h_int_rcp_gov_by_tx ; No - branch (this ensures soft spoolup by tx)
  2324. clr C
  2325. mov A, Requested_Pwm
  2326. subb A, #50 ; Is requested pwm below 20%?
  2327. jc t2h_int_rcp_gov_by_tx ; Yes - branch (this enables a soft spooldown)
  2328. mov Temp2, #Pgm_Gov_Setup_Target ; Gov by setup - load setup target
  2329. mov Requested_Pwm, @Temp2
  2330. t2h_int_rcp_gov_by_tx:
  2331. clr C
  2332. mov A, Governor_Req_Pwm
  2333. subb A, Requested_Pwm ; Is governor requested pwm equal to requested pwm?
  2334. jz t2h_int_rcp_gov_pwm_done ; Yes - branch
  2335. jc t2h_int_rcp_gov_pwm_inc ; No - if lower, then increment
  2336. dec Governor_Req_Pwm ; No - if higher, then decrement
  2337. ajmp t2h_int_rcp_gov_pwm_done
  2338. t2h_int_rcp_gov_pwm_inc:
  2339. inc Governor_Req_Pwm ; Increment
  2340. t2h_int_rcp_gov_pwm_done:
  2341. djnz Temp1, t2h_int_rcp_gov_pwm ; If not number of steps processed - go back
  2342. inc Spoolup_Limit_Cnt ; Increment spoolup count
  2343. mov A, Spoolup_Limit_Cnt
  2344. jnz ($+4) ; Wrapped?
  2345. dec Spoolup_Limit_Cnt ; Yes - decrement
  2346. djnz Spoolup_Limit_Skip, t2h_int_exit ; Jump if skip count is not reached
  2347. mov Spoolup_Limit_Skip, #1 ; Reset skip count. Default is fast spoolup
  2348. mov Temp1, #5 ; Default fast increase
  2349. clr C
  2350. mov A, Spoolup_Limit_Cnt
  2351. subb A, Main_Spoolup_Time_3x ; No spoolup until 3*N*32ms
  2352. jc t2h_int_exit
  2353. clr C
  2354. mov A, Spoolup_Limit_Cnt
  2355. subb A, Main_Spoolup_Time_10x ; Slow spoolup until "100"*N*32ms
  2356. jnc t2h_int_rcp_limit_middle_ramp
  2357. mov Temp1, #1 ; Slow initial spoolup
  2358. mov Spoolup_Limit_Skip, #3
  2359. jmp t2h_int_rcp_set_limit
  2360. t2h_int_rcp_limit_middle_ramp:
  2361. clr C
  2362. mov A, Spoolup_Limit_Cnt
  2363. subb A, Main_Spoolup_Time_15x ; Faster spoolup until "150"*N*32ms
  2364. jnc t2h_int_rcp_set_limit
  2365. mov Temp1, #1 ; Faster middle spoolup
  2366. mov Spoolup_Limit_Skip, #1
  2367. t2h_int_rcp_set_limit:
  2368. ; Do not increment spoolup limit if higher pwm is not requested, unless governor is active
  2369. clr C
  2370. mov A, Pwm_Limit_Spoolup
  2371. subb A, Current_Pwm
  2372. jc t2h_int_rcp_inc_limit ; If Current_Pwm is larger than Pwm_Limit_Spoolup - branch
  2373. mov Temp2, #Pgm_Gov_Mode ; Governor mode?
  2374. cjne @Temp2, #4, ($+5)
  2375. ajmp t2h_int_rcp_bailout_arm ; No - branch
  2376. mov A, Gov_Active ; Is governor active?
  2377. jnz t2h_int_rcp_inc_limit ; Yes - branch
  2378. mov Pwm_Limit_Spoolup, Current_Pwm ; Set limit to what current pwm is
  2379. mov A, Spoolup_Limit_Cnt ; Check if spoolup limit count is 255. If it is, then this is a "bailout" ramp
  2380. inc A
  2381. jz ($+5)
  2382. mov Spoolup_Limit_Cnt, Main_Spoolup_Time_3x ; Stay in an early part of the spoolup sequence (unless "bailout" ramp)
  2383. mov Spoolup_Limit_Skip, #1 ; Set skip count
  2384. mov Governor_Req_Pwm, #60 ; Set governor requested speed to ensure that it requests higher speed
  2385. ; 20=Fail on jerk when governor activates
  2386. ; 30=Ok
  2387. ; 100=Fail on small governor settling overshoot on low headspeeds
  2388. ; 200=Fail on governor settling overshoot
  2389. jmp t2h_int_exit ; Exit
  2390. t2h_int_rcp_inc_limit:
  2391. mov A, Pwm_Limit_Spoolup ; Increment spoolup pwm
  2392. add A, Temp1
  2393. jnc t2h_int_rcp_no_limit ; If below 255 - branch
  2394. mov Pwm_Limit_Spoolup, #0FFh
  2395. ajmp t2h_int_rcp_bailout_arm
  2396. t2h_int_rcp_no_limit:
  2397. mov Pwm_Limit_Spoolup, A
  2398. t2h_int_rcp_bailout_arm:
  2399. mov A, Pwm_Limit_Spoolup
  2400. inc A
  2401. jnz t2h_int_exit
  2402. mov Auto_Bailout_Armed, #255 ; Arm bailout
  2403. mov Spoolup_Limit_Cnt, #255
  2404. ENDIF
  2405. t2h_int_exit:
  2406. pop ACC ; Restore preserved registers
  2407. pop PSW
  2408. clr PSW.3 ; Select register bank 0 for main program routines
  2409. orl EIE1, #10h ; Enable PCA0 interrupts
  2410. setb ET2 ; Enable timer2 interrupts
  2411. reti
  2412. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  2413. ;
  2414. ; Timer3 interrupt routine
  2415. ;
  2416. ; No assumptions
  2417. ;
  2418. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  2419. t3_int: ; Used for commutation timing
  2420. push PSW ; Preserve registers through interrupt
  2421. push ACC
  2422. clr EA ; Disable all interrupts
  2423. anl TMR3CN, #7Fh ; Clear timer3 interrupt flag
  2424. anl EIE1, #7Fh ; Disable timer3 interrupts
  2425. clr Flags0.T3_PENDING ; Flag that timer has wrapped
  2426. IF MCU_50MHZ == 1
  2427. clr C
  2428. mov A, Next_Wt_L
  2429. rlc A
  2430. mov Next_Wt_L, A
  2431. mov A, Next_Wt_H
  2432. rlc A
  2433. mov Next_Wt_H, A
  2434. ENDIF
  2435. ; Set up next wait
  2436. mov TMR3CN, #00h ; Timer3 disabled
  2437. clr C
  2438. clr A
  2439. subb A, Next_Wt_L ; Set wait value
  2440. mov TMR3L, A
  2441. clr A
  2442. subb A, Next_Wt_H
  2443. mov TMR3H, A
  2444. mov TMR3CN, #04h ; Timer3 enabled
  2445. pop ACC ; Restore preserved registers
  2446. pop PSW
  2447. setb EA ; Enable all interrupts
  2448. reti
  2449. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  2450. ;
  2451. ; PCA interrupt routine
  2452. ;
  2453. ; No assumptions
  2454. ;
  2455. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  2456. pca_int: ; Used for RC pulse timing
  2457. clr EA
  2458. anl EIE1, #0EFh ; Disable PCA0 interrupts
  2459. clr ET2 ; Disable timer2 interrupts
  2460. push PSW ; Preserve registers through interrupt
  2461. push ACC
  2462. push B
  2463. setb PSW.3 ; Select register bank 1 for interrupt routines
  2464. setb EA
  2465. ; Get the PCA counter values
  2466. Get_Rcp_Capture_Values
  2467. ; Clear interrupt flag
  2468. Rcp_Clear_Int_Flag
  2469. ; Check which edge it is
  2470. jnb Flags2.RCP_EDGE_NO, ($+5) ; Is it a first edge trig?
  2471. ajmp pca_int_second_meas_pwm_freq ; No - branch to second
  2472. Rcp_Int_Second ; Yes - set second edge trig
  2473. setb Flags2.RCP_EDGE_NO ; Set second edge flag
  2474. ; Read RC signal level
  2475. Read_Rcp_Int
  2476. ; Test RC signal level
  2477. jb ACC.Rcp_In, ($+5) ; Is it high?
  2478. ajmp pca_int_fail_minimum ; No - jump to fail minimum
  2479. ; RC pulse was high, store RC pulse start timestamp
  2480. mov Rcp_Prev_Edge_L, Temp1
  2481. mov Rcp_Prev_Edge_H, Temp2
  2482. ajmp pca_int_exit ; Exit
  2483. pca_int_fail_minimum:
  2484. ; Prepare for next interrupt
  2485. Rcp_Int_First ; Set interrupt trig to first again
  2486. Rcp_Clear_Int_Flag ; Clear interrupt flag
  2487. clr Flags2.RCP_EDGE_NO ; Set first edge flag
  2488. jnb Flags2.RCP_PPM, ($+5) ; If flag is not set (PWM) - branch
  2489. ajmp pca_int_set_timeout ; If PPM - ignore trig as noise
  2490. mov Temp1, #RCP_MIN ; Set RC pulse value to minimum
  2491. Read_Rcp_Int ; Test RC signal level again
  2492. jnb ACC.Rcp_In, ($+5) ; Is it high?
  2493. ajmp pca_int_set_timeout ; Yes - set new timeout and exit
  2494. mov New_Rcp, Temp1 ; Store new pulse length
  2495. ajmp pca_int_limited ; Set new RC pulse, new timeout and exit
  2496. pca_int_second_meas_pwm_freq:
  2497. ; Prepare for next interrupt
  2498. Rcp_Int_First ; Set first edge trig
  2499. clr Flags2.RCP_EDGE_NO ; Set first edge flag
  2500. ; Check if pwm frequency shall be measured
  2501. jb Flags0.RCP_MEAS_PWM_FREQ, ($+5) ; Is measure RCP pwm frequency flag set?
  2502. ajmp pca_int_fall ; No - skip measurements
  2503. ; Set second edge trig only during pwm frequency measurement
  2504. Rcp_Int_Second ; Set second edge trig
  2505. Rcp_Clear_Int_Flag ; Clear interrupt flag
  2506. setb Flags2.RCP_EDGE_NO ; Set second edge flag
  2507. ; Store edge data to RAM
  2508. mov Rcp_Edge_L, Temp1
  2509. mov Rcp_Edge_H, Temp2
  2510. ; Calculate pwm frequency
  2511. clr C
  2512. mov A, Temp1
  2513. subb A, Rcp_PrePrev_Edge_L
  2514. mov Temp1, A
  2515. mov A, Temp2
  2516. subb A, Rcp_PrePrev_Edge_H
  2517. mov Temp2, A
  2518. clr A
  2519. mov Temp4, A
  2520. mov Temp7, #2 ; Set default period tolerance requirement (MSB)
  2521. mov Temp3, #0 ; (LSB)
  2522. ; Check if pulse is too short
  2523. clr C
  2524. mov A, Temp1
  2525. subb A, #low(140) ; If pulse below 70us, not accepted
  2526. mov A, Temp2
  2527. subb A, #high(140)
  2528. jnc rcp_int_check_12kHz
  2529. mov Rcp_Period_Diff_Accepted, #0 ; Set not accepted
  2530. ajmp pca_int_store_data
  2531. rcp_int_check_12kHz:
  2532. ; Check if pwm frequency is 12kHz
  2533. clr C
  2534. mov A, Temp1
  2535. subb A, #low(200) ; If below 100us, 12kHz pwm is assumed
  2536. mov A, Temp2
  2537. subb A, #high(200)
  2538. jnc pca_int_check_8kHz
  2539. clr A
  2540. setb ACC.RCP_PWM_FREQ_12KHZ
  2541. mov Temp4, A
  2542. mov Temp3, #10 ; Set period tolerance requirement (LSB)
  2543. ajmp pca_int_restore_edge_set_msb
  2544. pca_int_check_8kHz:
  2545. ; Check if pwm frequency is 8kHz
  2546. clr C
  2547. mov A, Temp1
  2548. subb A, #low(360) ; If below 180us, 8kHz pwm is assumed
  2549. mov A, Temp2
  2550. subb A, #high(360)
  2551. jnc pca_int_check_4kHz
  2552. clr A
  2553. setb ACC.RCP_PWM_FREQ_8KHZ
  2554. mov Temp4, A
  2555. mov Temp3, #15 ; Set period tolerance requirement (LSB)
  2556. ajmp pca_int_restore_edge_set_msb
  2557. pca_int_check_4kHz:
  2558. ; Check if pwm frequency is 4kHz
  2559. clr C
  2560. mov A, Temp1
  2561. subb A, #low(720) ; If below 360us, 4kHz pwm is assumed
  2562. mov A, Temp2
  2563. subb A, #high(720)
  2564. jnc pca_int_check_2kHz
  2565. clr A
  2566. setb ACC.RCP_PWM_FREQ_4KHZ
  2567. mov Temp4, A
  2568. mov Temp3, #30 ; Set period tolerance requirement (LSB)
  2569. ajmp pca_int_restore_edge_set_msb
  2570. pca_int_check_2kHz:
  2571. ; Check if pwm frequency is 2kHz
  2572. clr C
  2573. mov A, Temp1
  2574. subb A, #low(1440) ; If below 720us, 2kHz pwm is assumed
  2575. mov A, Temp2
  2576. subb A, #high(1440)
  2577. jnc pca_int_check_1kHz
  2578. clr A
  2579. setb ACC.RCP_PWM_FREQ_2KHZ
  2580. mov Temp4, A
  2581. mov Temp3, #60 ; Set period tolerance requirement (LSB)
  2582. ajmp pca_int_restore_edge_set_msb
  2583. pca_int_check_1kHz:
  2584. ; Check if pwm frequency is 1kHz
  2585. clr C
  2586. mov A, Temp1
  2587. subb A, #low(2200) ; If below 1100us, 1kHz pwm is assumed
  2588. mov A, Temp2
  2589. subb A, #high(2200)
  2590. jnc pca_int_restore_edge
  2591. clr A
  2592. setb ACC.RCP_PWM_FREQ_1KHZ
  2593. mov Temp4, A
  2594. mov Temp3, #120 ; Set period tolerance requirement (LSB)
  2595. pca_int_restore_edge_set_msb:
  2596. mov Temp7, #0 ; Set period tolerance requirement (MSB)
  2597. pca_int_restore_edge:
  2598. ; Calculate difference between this period and previous period
  2599. clr C
  2600. mov A, Temp1
  2601. subb A, Rcp_Prev_Period_L
  2602. mov Temp5, A
  2603. mov A, Temp2
  2604. subb A, Rcp_Prev_Period_H
  2605. mov Temp6, A
  2606. ; Make positive
  2607. jnb ACC.7, pca_int_check_diff
  2608. mov A, Temp5
  2609. cpl A
  2610. add A, #1
  2611. mov Temp5, A
  2612. mov A, Temp6
  2613. cpl A
  2614. mov Temp6, A
  2615. pca_int_check_diff:
  2616. ; Check difference
  2617. mov Rcp_Period_Diff_Accepted, #0 ; Set not accepted as default
  2618. clr C
  2619. mov A, Temp5
  2620. subb A, Temp3 ; Check difference
  2621. mov A, Temp6
  2622. subb A, Temp7
  2623. jnc pca_int_store_data
  2624. mov Rcp_Period_Diff_Accepted, #1 ; Set accepted
  2625. pca_int_store_data:
  2626. ; Store previous period
  2627. mov Rcp_Prev_Period_L, Temp1
  2628. mov Rcp_Prev_Period_H, Temp2
  2629. ; Restore edge data from RAM
  2630. mov Temp1, Rcp_Edge_L
  2631. mov Temp2, Rcp_Edge_H
  2632. ; Store pre previous edge
  2633. mov Rcp_PrePrev_Edge_L, Temp1
  2634. mov Rcp_PrePrev_Edge_H, Temp2
  2635. mov Temp1, #RCP_VALIDATE
  2636. ajmp pca_int_limited
  2637. pca_int_fall:
  2638. ; RC pulse edge was second, calculate new pulse length
  2639. clr C
  2640. mov A, Temp1
  2641. subb A, Rcp_Prev_Edge_L
  2642. mov Temp1, A
  2643. mov A, Temp2
  2644. subb A, Rcp_Prev_Edge_H
  2645. mov Temp2, A
  2646. jnb Flags3.RCP_PWM_FREQ_12KHZ, ($+5) ; Is RC input pwm frequency 12kHz?
  2647. ajmp pca_int_pwm_divide_done ; Yes - branch forward
  2648. jnb Flags3.RCP_PWM_FREQ_8KHZ, ($+5) ; Is RC input pwm frequency 8kHz?
  2649. ajmp pca_int_pwm_divide_done ; Yes - branch forward
  2650. jnb Flags3.RCP_PWM_FREQ_4KHZ, ($+5) ; Is RC input pwm frequency 4kHz?
  2651. ajmp pca_int_pwm_divide ; Yes - branch forward
  2652. jb Flags2.RCP_PPM_ONESHOT125, ($+5)
  2653. ajmp rcp_int_fall_not_oneshot
  2654. mov A, Temp2 ; Oneshot125 - move to I_Temp5/6
  2655. mov Temp6, A
  2656. mov A, Temp1
  2657. mov Temp5, A
  2658. ajmp rcp_int_fall_check_range
  2659. rcp_int_fall_not_oneshot:
  2660. mov A, Temp2 ; No - 2kHz. Divide by 2
  2661. clr C
  2662. rrc A
  2663. mov Temp2, A
  2664. mov A, Temp1
  2665. rrc A
  2666. mov Temp1, A
  2667. jnb Flags3.RCP_PWM_FREQ_2KHZ, ($+5) ; Is RC input pwm frequency 2kHz?
  2668. ajmp pca_int_pwm_divide ; Yes - branch forward
  2669. mov A, Temp2 ; No - 1kHz. Divide by 2 again
  2670. clr C
  2671. rrc A
  2672. mov Temp2, A
  2673. mov A, Temp1
  2674. rrc A
  2675. mov Temp1, A
  2676. jnb Flags3.RCP_PWM_FREQ_1KHZ, ($+5) ; Is RC input pwm frequency 1kHz?
  2677. ajmp pca_int_pwm_divide ; Yes - branch forward
  2678. mov A, Temp2 ; No - PPM. Divide by 2 (to bring range to 256) and move to Temp5/6
  2679. clr C
  2680. rrc A
  2681. mov Temp6, A
  2682. mov A, Temp1
  2683. rrc A
  2684. mov Temp5, A
  2685. rcp_int_fall_check_range:
  2686. ; Skip range limitation if pwm frequency measurement
  2687. jb Flags0.RCP_MEAS_PWM_FREQ, pca_int_ppm_check_full_range
  2688. ; Check if 2160us or above (in order to ignore false pulses)
  2689. clr C
  2690. mov A, Temp5 ; Is pulse 2160us or higher?
  2691. subb A, #28
  2692. mov A, Temp6
  2693. subb A, #2
  2694. jc ($+4) ; No - proceed
  2695. ajmp pca_int_ppm_outside_range ; Yes - ignore pulse
  2696. pca_int_ppm_below_full_range:
  2697. ; Check if below 800us (in order to ignore false pulses)
  2698. mov A, Temp6
  2699. jnz pca_int_ppm_check_full_range
  2700. clr C
  2701. mov A, Temp5 ; Is pulse below 800us?
  2702. subb A, #200
  2703. jnc pca_int_ppm_check_full_range ; No - proceed
  2704. pca_int_ppm_outside_range:
  2705. inc Rcp_Outside_Range_Cnt
  2706. clr C
  2707. mov A, Rcp_Outside_Range_Cnt
  2708. subb A, #10 ; Allow a given number of outside pulses
  2709. jnc ($+4)
  2710. ajmp pca_int_set_timeout ; If below limit - ignore pulse
  2711. mov New_Rcp, #0 ; Set pulse length to zero
  2712. setb Flags2.RCP_UPDATED ; Set updated flag
  2713. ajmp pca_int_set_timeout
  2714. pca_int_ppm_check_full_range:
  2715. mov A, Rcp_Outside_Range_Cnt
  2716. jz ($+4)
  2717. dec Rcp_Outside_Range_Cnt
  2718. ; Calculate "1000us" plus throttle minimum
  2719. mov A, #0 ; Set 1000us as default minimum
  2720. jb Flags3.FULL_THROTTLE_RANGE, pca_int_ppm_calculate ; Check if full range is chosen
  2721. IF MODE >= 1 ; Tail or multi
  2722. mov Temp1, #Pgm_Direction ; Check if bidirectional operation
  2723. mov A, @Temp1
  2724. ENDIF
  2725. mov Temp1, #Pgm_Ppm_Min_Throttle ; Min throttle value is in 4us units
  2726. IF MODE >= 1 ; Tail or multi
  2727. cjne A, #3, ($+5)
  2728. mov Temp1, #Pgm_Ppm_Center_Throttle ; Center throttle value is in 4us units
  2729. ENDIF
  2730. mov A, @Temp1
  2731. pca_int_ppm_calculate:
  2732. add A, #250 ; Add 1000us to minimum
  2733. mov Temp7, A
  2734. clr A
  2735. addc A, #0
  2736. mov Temp8, A
  2737. clr C
  2738. mov A, Temp5 ; Subtract minimum
  2739. subb A, Temp7
  2740. mov Temp5, A
  2741. mov A, Temp6
  2742. subb A, Temp8
  2743. mov Temp6, A
  2744. IF MODE >= 1 ; Tail or multi
  2745. mov Bit_Access_Int.0, C
  2746. mov Temp1, #Pgm_Direction ; Check if bidirectional operation
  2747. mov A, @Temp1
  2748. cjne A, #3, pca_int_ppm_bidir_dir_set ; No - branch
  2749. mov C, Bit_Access_Int.0
  2750. jnc pca_int_ppm_bidir_fwd ; If result is positive - branch
  2751. pca_int_ppm_bidir_rev:
  2752. jb Flags3.PGM_DIR_REV, pca_int_ppm_bidir_dir_set ; If same direction - branch
  2753. clr EA ; Direction change, turn off all fets
  2754. setb Flags3.PGM_DIR_REV
  2755. ajmp pca_int_ppm_bidir_dir_change
  2756. pca_int_ppm_bidir_fwd:
  2757. jnb Flags3.PGM_DIR_REV, pca_int_ppm_bidir_dir_set ; If same direction - branch
  2758. clr EA ; Direction change, turn off all fets
  2759. clr Flags3.PGM_DIR_REV
  2760. pca_int_ppm_bidir_dir_change:
  2761. All_nFETs_Off
  2762. All_pFETs_Off
  2763. jb Flags1.STARTUP_PHASE, ($+5) ; Do not brake when starting
  2764. setb Flags1.DIR_CHANGE_BRAKE ; Set brake flag
  2765. setb EA
  2766. pca_int_ppm_bidir_dir_set:
  2767. mov C, Bit_Access_Int.0
  2768. ENDIF
  2769. jnc pca_int_ppm_neg_checked ; If result is positive - branch
  2770. IF MODE >= 1 ; Tail or multi
  2771. mov A, @Temp1 ; Check if bidirectional operation (Temp1 has Pgm_Direction)
  2772. cjne A, #3, pca_int_ppm_unidir_neg ; No - branch
  2773. mov A, Temp5 ; Change sign
  2774. cpl A
  2775. add A, #1
  2776. mov Temp5, A
  2777. mov A, Temp6
  2778. cpl A
  2779. addc A, #0
  2780. mov Temp6, A
  2781. jmp pca_int_ppm_neg_checked
  2782. pca_int_ppm_unidir_neg:
  2783. ENDIF
  2784. mov Temp1, #RCP_MIN ; Yes - set to minimum
  2785. mov Temp2, #0
  2786. ajmp pca_int_pwm_divide_done
  2787. pca_int_ppm_neg_checked:
  2788. IF MODE >= 1 ; Tail or multi
  2789. mov Temp1, #Pgm_Direction ; Check if bidirectional operation
  2790. mov A, @Temp1
  2791. cjne A, #3, pca_int_ppm_bidir_done ; No - branch
  2792. mov A, Temp5 ; Multiply value by 2
  2793. rlc A
  2794. mov Temp5 A
  2795. mov A, Temp6
  2796. rlc A
  2797. mov Temp6 A
  2798. clr C ; Subtract deadband
  2799. mov A, Temp5
  2800. subb A, #10
  2801. mov Temp5, A
  2802. mov A, Temp6
  2803. subb A, #0
  2804. mov Temp6, A
  2805. jnc pca_int_ppm_bidir_done
  2806. mov Temp5, #RCP_MIN
  2807. mov Temp6, #0
  2808. pca_int_ppm_bidir_done:
  2809. ENDIF
  2810. clr C ; Check that RC pulse is within legal range (max 255)
  2811. mov A, Temp5
  2812. subb A, #RCP_MAX
  2813. mov A, Temp6
  2814. subb A, #0
  2815. jc pca_int_ppm_max_checked
  2816. mov Temp1, #RCP_MAX
  2817. mov Temp2, #0
  2818. ajmp pca_int_pwm_divide_done
  2819. pca_int_ppm_max_checked:
  2820. mov A, Temp5 ; Multiply throttle value by gain
  2821. mov B, Ppm_Throttle_Gain
  2822. mul AB
  2823. xch A, B
  2824. mov C, B.7 ; Multiply result by 2 (unity gain is 128)
  2825. rlc A
  2826. mov Temp1, A ; Transfer to Temp1/2
  2827. mov Temp2, #0
  2828. jc pca_int_ppm_limit_after_mult
  2829. jmp pca_int_limited
  2830. pca_int_ppm_limit_after_mult:
  2831. mov Temp1, #RCP_MAX
  2832. mov Temp2, #0
  2833. jmp pca_int_limited
  2834. pca_int_pwm_divide:
  2835. mov A, Temp2 ; Divide by 2
  2836. clr C
  2837. rrc A
  2838. mov Temp2, A
  2839. mov A, Temp1
  2840. rrc A
  2841. mov Temp1, A
  2842. pca_int_pwm_divide_done:
  2843. jnb Flags3.RCP_PWM_FREQ_12KHZ, pca_int_check_legal_range ; Is RC input pwm frequency 12kHz?
  2844. mov A, Temp2 ; Yes - check that value is not more than 255
  2845. jz ($+4)
  2846. mov Temp1, #RCP_MAX
  2847. clr C
  2848. mov A, Temp1 ; Multiply by 1.5
  2849. rrc A
  2850. addc A, Temp1
  2851. mov Temp1, A
  2852. clr A
  2853. addc A, #0
  2854. mov Temp2, A
  2855. pca_int_check_legal_range:
  2856. ; Check that RC pulse is within legal range
  2857. clr C
  2858. mov A, Temp1
  2859. subb A, #RCP_MAX
  2860. mov A, Temp2
  2861. subb A, #0
  2862. jc pca_int_limited
  2863. mov Temp1, #RCP_MAX
  2864. pca_int_limited:
  2865. ; RC pulse value accepted
  2866. mov New_Rcp, Temp1 ; Store new pulse length
  2867. setb Flags2.RCP_UPDATED ; Set updated flag
  2868. jb Flags0.RCP_MEAS_PWM_FREQ, ($+5) ; Is measure RCP pwm frequency flag set?
  2869. ajmp pca_int_set_timeout ; No - skip measurements
  2870. mov A, #((1 SHL RCP_PWM_FREQ_1KHZ)+(1 SHL RCP_PWM_FREQ_2KHZ)+(1 SHL RCP_PWM_FREQ_4KHZ)+(1 SHL RCP_PWM_FREQ_8KHZ)+(1 SHL RCP_PWM_FREQ_12KHZ))
  2871. cpl A
  2872. anl A, Flags3 ; Clear all pwm frequency flags
  2873. orl A, Temp4 ; Store pwm frequency value in flags
  2874. mov Flags3, A
  2875. clr Flags2.RCP_PPM ; Default, flag is not set (PWM)
  2876. clr A
  2877. add A, Temp4 ; Check if all flags are cleared
  2878. jnz pca_int_set_timeout
  2879. setb Flags2.RCP_PPM ; Set flag (PPM)
  2880. pca_int_set_timeout:
  2881. mov Rcp_Timeout_Cnt, #RCP_TIMEOUT ; Set timeout count to start value
  2882. jnb Flags2.RCP_PPM, pca_int_ppm_timeout_set ; If flag is not set (PWM) - branch
  2883. mov Rcp_Timeout_Cnt, #RCP_TIMEOUT_PPM ; No flag set means PPM. Set timeout count
  2884. pca_int_ppm_timeout_set:
  2885. jnb Flags0.RCP_MEAS_PWM_FREQ, ($+5) ; Is measure RCP pwm frequency flag set?
  2886. ajmp pca_int_exit ; Yes - exit
  2887. jb Flags2.RCP_PPM, pca_int_exit ; If flag is set (PPM) - branch
  2888. Rcp_Int_Disable ; Disable RC pulse interrupt
  2889. pca_int_exit: ; Exit interrupt routine
  2890. mov Rcp_Skip_Cnt, #RCP_SKIP_RATE ; Load number of skips
  2891. jnb Flags2.RCP_PPM, ($+6) ; If flag is not set (PWM) - branch
  2892. mov Rcp_Skip_Cnt, #10 ; Load number of skips
  2893. pop B ; Restore preserved registers
  2894. pop ACC
  2895. pop PSW
  2896. clr PSW.3 ; Select register bank 0 for main program routines
  2897. setb ET2 ; Enable timer2 interrupts
  2898. orl EIE1, #10h ; Enable PCA0 interrupts
  2899. reti
  2900. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  2901. ;
  2902. ; Wait xms ~(x*4*250) (Different entry points)
  2903. ;
  2904. ; No assumptions
  2905. ;
  2906. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  2907. wait1ms:
  2908. mov Temp2, #1
  2909. jmp waitxms_o
  2910. wait3ms:
  2911. mov Temp2, #3
  2912. jmp waitxms_o
  2913. wait10ms:
  2914. mov Temp2, #10
  2915. jmp waitxms_o
  2916. wait30ms:
  2917. mov Temp2, #30
  2918. jmp waitxms_o
  2919. wait100ms:
  2920. mov Temp2, #100
  2921. jmp waitxms_o
  2922. wait200ms:
  2923. mov Temp2, #200
  2924. jmp waitxms_o
  2925. waitxms_o: ; Outer loop
  2926. mov Temp1, #23
  2927. waitxms_m: ; Middle loop
  2928. clr A
  2929. djnz ACC, $ ; Inner loop (42.7us - 1024 cycles)
  2930. djnz Temp1, waitxms_m
  2931. djnz Temp2, waitxms_o
  2932. ret
  2933. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  2934. ;
  2935. ; Beeper routines (4 different entry points)
  2936. ;
  2937. ; No assumptions
  2938. ;
  2939. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  2940. beep_f1: ; Entry point 1, load beeper frequency 1 settings
  2941. mov Temp3, #20 ; Off wait loop length
  2942. mov Temp4, #120 ; Number of beep pulses
  2943. jmp beep
  2944. beep_f2: ; Entry point 2, load beeper frequency 2 settings
  2945. mov Temp3, #16
  2946. mov Temp4, #140
  2947. jmp beep
  2948. beep_f3: ; Entry point 3, load beeper frequency 3 settings
  2949. mov Temp3, #13
  2950. mov Temp4, #180
  2951. jmp beep
  2952. beep_f4: ; Entry point 4, load beeper frequency 4 settings
  2953. mov Temp3, #11
  2954. mov Temp4, #200
  2955. jmp beep
  2956. beep: ; Beep loop start
  2957. mov Temp5, Current_Pwm_Limited ; Store value
  2958. mov Current_Pwm_Limited, #1 ; Set to a nonzero value
  2959. mov Temp2, #2 ; Must be an even number (or direction will change)
  2960. beep_onoff:
  2961. cpl Flags3.PGM_DIR_REV ; Toggle between using A fet and C fet
  2962. clr A
  2963. BpFET_off ; BpFET off
  2964. djnz ACC, $ ; Allow some time after pfet is turned off
  2965. BnFET_on ; BnFET on (in order to charge the driver of the BpFET)
  2966. djnz ACC, $ ; Let the nfet be turned on a while
  2967. BnFET_off ; BnFET off again
  2968. djnz ACC, $ ; Allow some time after nfet is turned off
  2969. BpFET_on ; BpFET on
  2970. djnz ACC, $ ; Allow some time after pfet is turned on
  2971. ; Turn on nfet
  2972. AnFET_on ; AnFET on
  2973. mov A, Beep_Strength
  2974. djnz ACC, $
  2975. ; Turn off nfet
  2976. AnFET_off ; AnFET off
  2977. mov A, #150 ; 25�s off
  2978. djnz ACC, $
  2979. djnz Temp2, beep_onoff
  2980. ; Copy variable
  2981. mov A, Temp3
  2982. mov Temp1, A
  2983. beep_off: ; Fets off loop
  2984. djnz ACC, $
  2985. djnz Temp1, beep_off
  2986. djnz Temp4, beep
  2987. BpFET_off ; BpFET off
  2988. mov Current_Pwm_Limited, Temp5 ; Restore value
  2989. ret
  2990. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  2991. ;
  2992. ; Division 16bit unsigned by 16bit unsigned
  2993. ;
  2994. ; Dividend shall be in Temp2/Temp1, divisor in Temp4/Temp3
  2995. ; Result will be in Temp2/Temp1
  2996. ;
  2997. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  2998. div_u16_by_u16:
  2999. clr C
  3000. mov Temp5, #0
  3001. mov Temp6, #0
  3002. mov B, #0
  3003. div_u16_by_u16_div1:
  3004. inc B ; Increment counter for each left shift
  3005. mov A, Temp3 ; Shift left the divisor
  3006. rlc A
  3007. mov Temp3, A
  3008. mov A, Temp4
  3009. rlc A
  3010. mov Temp4, A
  3011. jnc div_u16_by_u16_div1 ; Repeat until carry flag is set from high-byte
  3012. div_u16_by_u16_div2:
  3013. mov A, Temp4 ; Shift right the divisor
  3014. rrc A
  3015. mov Temp4, A
  3016. mov A, Temp3
  3017. rrc A
  3018. mov Temp3, A
  3019. clr C
  3020. mov A, Temp2 ; Make a safe copy of the dividend
  3021. mov Temp8, A
  3022. mov A, Temp1
  3023. mov Temp7, A
  3024. mov A, Temp1 ; Move low-byte of dividend into accumulator
  3025. subb A, Temp3 ; Dividend - shifted divisor = result bit (no factor, only 0 or 1)
  3026. mov Temp1, A ; Save updated dividend
  3027. mov A, Temp2 ; Move high-byte of dividend into accumulator
  3028. subb A, Temp4 ; Subtract high-byte of divisor (all together 16-bit substraction)
  3029. mov Temp2, A ; Save updated high-byte back in high-byte of divisor
  3030. jnc div_u16_by_u16_div3 ; If carry flag is NOT set, result is 1
  3031. mov A, Temp8 ; Otherwise result is 0, save copy of divisor to undo subtraction
  3032. mov Temp2, A
  3033. mov A, Temp7
  3034. mov Temp1, A
  3035. div_u16_by_u16_div3:
  3036. cpl C ; Invert carry, so it can be directly copied into result
  3037. mov A, Temp5
  3038. rlc A ; Shift carry flag into temporary result
  3039. mov Temp5, A
  3040. mov A, Temp6
  3041. rlc A
  3042. mov Temp6,A
  3043. djnz B, div_u16_by_u16_div2 ;Now count backwards and repeat until "B" is zero
  3044. mov A, Temp6 ; Move result to Temp2/Temp1
  3045. mov Temp2, A
  3046. mov A, Temp5
  3047. mov Temp1, A
  3048. ret
  3049. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  3050. ;
  3051. ; Multiplication 16bit signed by 8bit unsigned
  3052. ;
  3053. ; Multiplicand shall be in Temp2/Temp1, multiplicator in Temp3
  3054. ; Result will be in Temp2/Temp1. Result will divided by 16
  3055. ;
  3056. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  3057. mult_s16_by_u8_div_16:
  3058. mov A, Temp1 ; Read input to math registers
  3059. mov B, Temp2
  3060. mov Bit_Access, Temp3
  3061. setb PSW.4 ; Select register bank 2 for math routines
  3062. mov Temp1, A ; Store in math registers
  3063. mov Temp2, B
  3064. mov Temp4, #0 ; Set sign in Temp4 and test sign
  3065. jnb B.7, mult_s16_by_u8_positive
  3066. mov Temp4, #0FFh
  3067. cpl A
  3068. add A, #1
  3069. mov Temp1, A
  3070. mov A, Temp2
  3071. cpl A
  3072. addc A, #0
  3073. mov Temp2, A
  3074. mult_s16_by_u8_positive:
  3075. mov A, Temp1 ; Multiply LSB with multiplicator
  3076. mov B, Bit_Access
  3077. mul AB
  3078. mov Temp6, B ; Place MSB in Temp6
  3079. mov Temp1, A ; Place LSB in Temp1 (result)
  3080. mov A, Temp2 ; Multiply MSB with multiplicator
  3081. mov B, Bit_Access
  3082. mul AB
  3083. mov Temp8, B ; Place in Temp8/7
  3084. mov Temp7, A
  3085. mov A, Temp6 ; Add up
  3086. add A, Temp7
  3087. mov Temp2, A
  3088. mov A, #0
  3089. addc A, Temp8
  3090. mov Temp3, A
  3091. mov Temp5, #4 ; Set number of divisions
  3092. mult_s16_by_u8_div_loop:
  3093. clr C ; Rotate right
  3094. mov A, Temp3
  3095. rrc A
  3096. mov Temp3, A
  3097. mov A, Temp2
  3098. rrc A
  3099. mov Temp2, A
  3100. mov A, Temp1
  3101. rrc A
  3102. mov Temp1, A
  3103. djnz Temp5, mult_s16_by_u8_div_loop
  3104. mov B, Temp4 ; Test sign
  3105. jnb B.7, mult_s16_by_u8_exit
  3106. mov A, Temp1
  3107. cpl A
  3108. add A, #1
  3109. mov Temp1, A
  3110. mov A, Temp2
  3111. cpl A
  3112. addc A, #0
  3113. mov Temp2, A
  3114. mult_s16_by_u8_exit:
  3115. mov A, Temp1 ; Store output
  3116. mov B, Temp2
  3117. clr PSW.4 ; Select normal register bank
  3118. mov Temp1, A
  3119. mov Temp2, B
  3120. ret
  3121. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  3122. ;
  3123. ; Calculate governor routines
  3124. ;
  3125. ; No assumptions
  3126. ;
  3127. ; Governs headspeed based upon the Comm_Period4x variable and pwm
  3128. ; The governor task is split into several routines in order to distribute processing time
  3129. ;
  3130. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  3131. ; First governor routine - calculate governor target
  3132. IF MODE == 0 ; Main
  3133. calc_governor_target:
  3134. mov Temp1, #Pgm_Gov_Mode ; Governor mode?
  3135. cjne @Temp1, #4, governor_speed_check ; Yes
  3136. jmp calc_governor_target_exit ; No
  3137. governor_speed_check:
  3138. ; Stop governor for stop RC pulse
  3139. clr C
  3140. mov A, New_Rcp ; Check RC pulse against stop value
  3141. subb A, #(RCP_MAX/10) ; Is pulse below stop value?
  3142. jc governor_deactivate ; Yes - deactivate
  3143. mov A, Flags1
  3144. anl A, #((1 SHL STARTUP_PHASE)+(1 SHL INITIAL_RUN_PHASE))
  3145. jnz governor_deactivate ; Deactivate if any startup phase set
  3146. ; Skip speed check if governor is already active
  3147. mov A, Gov_Active
  3148. jnz governor_target_calc
  3149. ; Check speed (do not run governor for low speeds)
  3150. mov Temp1, #05h ; Default high range activation limit value (~62500 eRPM)
  3151. mov Temp2, #Pgm_Gov_Range
  3152. mov A, @Temp2 ; Check if high range (Temp2 has #Pgm_Gov_Range)
  3153. dec A
  3154. jz governor_act_lim_set ; If high range - branch
  3155. mov Temp1, #0Ah ; Middle range activation limit value (~31250 eRPM)
  3156. dec A
  3157. jz governor_act_lim_set ; If middle range - branch
  3158. mov Temp1, #12h ; Low range activation limit value (~17400 eRPM)
  3159. governor_act_lim_set:
  3160. clr C
  3161. mov A, Comm_Period4x_H
  3162. subb A, Temp1
  3163. jc governor_activate ; If speed above min limit - run governor
  3164. governor_deactivate:
  3165. mov A, Gov_Active
  3166. jz governor_first_deactivate_done; This code is executed continuously. Only execute the code below the first time
  3167. mov Pwm_Limit_Spoolup, Pwm_Spoolup_Beg
  3168. mov Spoolup_Limit_Cnt, #255
  3169. mov Spoolup_Limit_Skip, #1
  3170. governor_first_deactivate_done:
  3171. mov Current_Pwm, Requested_Pwm ; Set current pwm to requested
  3172. clr A
  3173. mov Gov_Target_L, A ; Set target to zero
  3174. mov Gov_Target_H, A
  3175. mov Gov_Integral_L, A ; Set integral to zero
  3176. mov Gov_Integral_H, A
  3177. mov Gov_Integral_X, A
  3178. mov Gov_Active, A
  3179. jmp calc_governor_target_exit
  3180. governor_activate:
  3181. mov Gov_Active, #1
  3182. governor_target_calc:
  3183. ; Governor calculations
  3184. mov Temp2, #Pgm_Gov_Range
  3185. mov A, @Temp2 ; Check high, middle or low range
  3186. dec A
  3187. jnz calc_governor_target_middle
  3188. mov A, Governor_Req_Pwm ; Load governor requested pwm
  3189. cpl A ; Calculate 255-pwm (invert pwm)
  3190. ; Calculate comm period target (1 + 2*((255-Requested_Pwm)/256) - 0.25)
  3191. rlc A ; Msb to carry
  3192. rlc A ; To bit0
  3193. mov Temp2, A ; Now 1 lsb is valid for H
  3194. rrc A
  3195. mov Temp1, A ; Now 7 msbs are valid for L
  3196. mov A, Temp2
  3197. anl A, #01h ; Calculate H byte
  3198. inc A ; Add 1
  3199. mov Temp2, A
  3200. mov A, Temp1
  3201. anl A, #0FEh ; Calculate L byte
  3202. jmp calc_governor_subtract_025
  3203. calc_governor_target_middle:
  3204. mov A, @Temp2 ; Check middle or low range (Temp2 has #Pgm_Gov_Range)
  3205. dec A
  3206. dec A
  3207. jnz calc_governor_target_low
  3208. mov A, Governor_Req_Pwm ; Load governor requested pwm
  3209. cpl A ; Calculate 255-pwm (invert pwm)
  3210. ; Calculate comm period target (1 + 4*((255-Requested_Pwm)/256))
  3211. rlc A ; Msb to carry
  3212. rlc A ; To bit0
  3213. rlc A ; To bit1
  3214. mov Temp2, A ; Now 2 lsbs are valid for H
  3215. rrc A
  3216. mov Temp1, A ; Now 6 msbs are valid for L
  3217. mov A, Temp2
  3218. anl A, #03h ; Calculate H byte
  3219. inc A ; Add 1
  3220. mov Temp2, A
  3221. mov A, Temp1
  3222. anl A, #0FCh ; Calculate L byte
  3223. jmp calc_governor_store_target
  3224. calc_governor_target_low:
  3225. mov A, Governor_Req_Pwm ; Load governor requested pwm
  3226. cpl A ; Calculate 255-pwm (invert pwm)
  3227. ; Calculate comm period target (2 + 8*((255-Requested_Pwm)/256) - 0.25)
  3228. rlc A ; Msb to carry
  3229. rlc A ; To bit0
  3230. rlc A ; To bit1
  3231. rlc A ; To bit2
  3232. mov Temp2, A ; Now 3 lsbs are valid for H
  3233. rrc A
  3234. mov Temp1, A ; Now 5 msbs are valid for L
  3235. mov A, Temp2
  3236. anl A, #07h ; Calculate H byte
  3237. inc A ; Add 1
  3238. inc A ; Add 1 more
  3239. mov Temp2, A
  3240. mov A, Temp1
  3241. anl A, #0F8h ; Calculate L byte
  3242. calc_governor_subtract_025:
  3243. clr C
  3244. subb A, #40h ; Subtract 0.25
  3245. mov Temp1, A
  3246. mov A, Temp2
  3247. subb A, #0
  3248. mov Temp2, A
  3249. calc_governor_store_target:
  3250. ; Store governor target
  3251. mov Gov_Target_L, Temp1
  3252. mov Gov_Target_H, Temp2
  3253. calc_governor_target_exit:
  3254. ret
  3255. ENDIF
  3256. IF MODE == 1 ; Tail
  3257. calc_governor_target:
  3258. ret
  3259. ENDIF
  3260. IF MODE == 2 ; Multi
  3261. calc_governor_target:
  3262. mov Temp1, #Pgm_Gov_Mode ; Closed loop mode?
  3263. cjne @Temp1, #4, governor_target_calc ; Yes - branch
  3264. jmp calc_governor_target_exit ; No
  3265. governor_target_calc:
  3266. ; Stop governor for stop RC pulse
  3267. clr C
  3268. mov A, New_Rcp ; Check RC pulse against stop value
  3269. subb A, #RCP_STOP ; Is pulse below stop value?
  3270. jc governor_deactivate ; Yes - deactivate
  3271. jmp governor_activate ; No - activate
  3272. governor_deactivate:
  3273. mov Current_Pwm, Requested_Pwm ; Set current pwm to requested
  3274. clr A
  3275. mov Gov_Target_L, A ; Set target to zero
  3276. mov Gov_Target_H, A
  3277. mov Gov_Integral_L, A ; Set integral to zero
  3278. mov Gov_Integral_H, A
  3279. mov Gov_Integral_X, A
  3280. mov Gov_Active, A
  3281. jmp calc_governor_target_exit
  3282. governor_activate:
  3283. mov Temp1, #Pgm_Gov_Mode ; Store gov mode
  3284. mov A, @Temp1
  3285. mov Temp5, A
  3286. mov Gov_Active, #1
  3287. mov A, Requested_Pwm ; Load requested pwm
  3288. mov Governor_Req_Pwm, A ; Set governor requested pwm
  3289. ; Calculate comm period target 2*(51000/Requested_Pwm)
  3290. mov Temp1, #38h ; Load 51000
  3291. mov Temp2, #0C7h
  3292. mov Temp3, Comm_Period4x_L ; Load comm period
  3293. mov Temp4, Comm_Period4x_H
  3294. ; Set speed range. Bare Comm_Period4x corresponds to 400k eRPM, because it is 500n units
  3295. clr C
  3296. mov A, Temp4
  3297. rrc A
  3298. mov Temp4, A
  3299. mov A, Temp3
  3300. rrc A
  3301. mov Temp3, A ; 200k eRPM range here
  3302. ; Check range
  3303. mov A, Temp5
  3304. dec A
  3305. jz governor_activate_range_set ; 200k eRPM? - branch
  3306. governor_activate_100k:
  3307. clr C
  3308. mov A, Temp4
  3309. rrc A
  3310. mov Temp4, A
  3311. mov A, Temp3
  3312. rrc A
  3313. mov Temp3, A ; 100k eRPM range here
  3314. mov A, Temp5 ; Check range again
  3315. dec A
  3316. dec A
  3317. jz governor_activate_range_set ; 100k eRPM? - branch
  3318. governor_activate_50k:
  3319. clr C
  3320. mov A, Temp4
  3321. rrc A
  3322. mov Temp4, A
  3323. mov A, Temp3
  3324. rrc A
  3325. mov Temp3, A ; 50k eRPM range here
  3326. governor_activate_range_set:
  3327. call div_u16_by_u16
  3328. ; Store governor target
  3329. mov Gov_Target_L, Temp1
  3330. mov Gov_Target_H, Temp2
  3331. calc_governor_target_exit:
  3332. ret
  3333. ENDIF
  3334. ; Second governor routine - calculate governor proportional error
  3335. calc_governor_prop_error:
  3336. ; Exit if governor is inactive
  3337. mov A, Gov_Active
  3338. jz calc_governor_prop_error_exit
  3339. IF MODE <= 1 ; Main or tail
  3340. ; Load comm period and divide by 2
  3341. clr C
  3342. mov A, Comm_Period4x_H
  3343. rrc A
  3344. mov Temp2, A
  3345. mov A, Comm_Period4x_L
  3346. rrc A
  3347. mov Temp1, A
  3348. ; Calculate error
  3349. clr C
  3350. mov A, Gov_Target_L
  3351. subb A, Temp1
  3352. mov Temp1, A
  3353. mov A, Gov_Target_H
  3354. subb A, Temp2
  3355. mov Temp2, A
  3356. ENDIF
  3357. IF MODE == 2 ; Multi
  3358. ; Calculate error
  3359. clr C
  3360. mov A, Gov_Target_L
  3361. subb A, Governor_Req_Pwm
  3362. mov Temp1, A
  3363. mov A, Gov_Target_H
  3364. subb A, #0
  3365. mov Temp2, A
  3366. ENDIF
  3367. ; Check error and limit
  3368. jnc governor_check_prop_limit_pos ; Check carry
  3369. clr C
  3370. mov A, Temp1
  3371. subb A, #80h ; Is error too negative?
  3372. mov A, Temp2
  3373. subb A, #0FFh
  3374. jc governor_limit_prop_error_neg ; Yes - limit
  3375. jmp governor_store_prop_error
  3376. governor_check_prop_limit_pos:
  3377. clr C
  3378. mov A, Temp1
  3379. subb A, #7Fh ; Is error too positive?
  3380. mov A, Temp2
  3381. subb A, #00h
  3382. jnc governor_limit_prop_error_pos ; Yes - limit
  3383. jmp governor_store_prop_error
  3384. governor_limit_prop_error_pos:
  3385. mov Temp1, #7Fh ; Limit to max positive (2's complement)
  3386. mov Temp2, #00h
  3387. jmp governor_store_prop_error
  3388. governor_limit_prop_error_neg:
  3389. mov Temp1, #80h ; Limit to max negative (2's complement)
  3390. mov Temp2, #0FFh
  3391. governor_store_prop_error:
  3392. ; Store proportional
  3393. mov Gov_Proportional_L, Temp1
  3394. mov Gov_Proportional_H, Temp2
  3395. calc_governor_prop_error_exit:
  3396. ret
  3397. ; Third governor routine - calculate governor integral error
  3398. calc_governor_int_error:
  3399. ; Exit if governor is inactive
  3400. mov A, Gov_Active
  3401. jz calc_governor_int_error_exit
  3402. ; Add proportional to integral
  3403. mov A, Gov_Proportional_L
  3404. add A, Gov_Integral_L
  3405. mov Temp1, A
  3406. mov A, Gov_Proportional_H
  3407. addc A, Gov_Integral_H
  3408. mov Temp2, A
  3409. mov Bit_Access, Gov_Proportional_H ; Sign extend high byte
  3410. clr A
  3411. jnb Bit_Access.7, ($+4)
  3412. cpl A
  3413. addc A, Gov_Integral_X
  3414. mov Temp3, A
  3415. ; Check integral and limit
  3416. jnb ACC.7, governor_check_int_limit_pos ; Check sign bit
  3417. clr C
  3418. mov A, Temp3
  3419. subb A, #0F0h ; Is error too negative?
  3420. jc governor_limit_int_error_neg ; Yes - limit
  3421. jmp governor_check_pwm
  3422. governor_check_int_limit_pos:
  3423. clr C
  3424. mov A, Temp3
  3425. subb A, #0Fh ; Is error too positive?
  3426. jnc governor_limit_int_error_pos ; Yes - limit
  3427. jmp governor_check_pwm
  3428. governor_limit_int_error_pos:
  3429. mov Temp1, #0FFh ; Limit to max positive (2's complement)
  3430. mov Temp2, #0FFh
  3431. mov Temp3, #0Fh
  3432. jmp governor_check_pwm
  3433. governor_limit_int_error_neg:
  3434. mov Temp1, #00h ; Limit to max negative (2's complement)
  3435. mov Temp2, #00h
  3436. mov Temp3, #0F0h
  3437. governor_check_pwm:
  3438. ; Check current pwm
  3439. clr C
  3440. mov A, Current_Pwm
  3441. subb A, Pwm_Limit ; Is current pwm at or above pwm limit?
  3442. jnc governor_int_max_pwm ; Yes - branch
  3443. mov A, Current_Pwm ; Is current pwm at zero?
  3444. jz governor_int_min_pwm ; Yes - branch
  3445. ajmp governor_store_int_error ; No - store integral error
  3446. governor_int_max_pwm:
  3447. mov A, Gov_Proportional_H
  3448. jb ACC.7, calc_governor_int_error_exit ; Is proportional error negative - branch (high byte is always zero)
  3449. ajmp governor_store_int_error ; Positive - store integral error
  3450. governor_int_min_pwm:
  3451. mov A, Gov_Proportional_H
  3452. jnb ACC.7, calc_governor_int_error_exit ; Is proportional error positive - branch (high byte is always zero)
  3453. governor_store_int_error:
  3454. ; Store integral
  3455. mov Gov_Integral_L, Temp1
  3456. mov Gov_Integral_H, Temp2
  3457. mov Gov_Integral_X, Temp3
  3458. calc_governor_int_error_exit:
  3459. ret
  3460. ; Fourth governor routine - calculate governor proportional correction
  3461. calc_governor_prop_correction:
  3462. ; Exit if governor is inactive
  3463. mov A, Gov_Active
  3464. jnz calc_governor_prop_corr
  3465. jmp calc_governor_prop_corr_exit
  3466. calc_governor_prop_corr:
  3467. ; Load proportional gain
  3468. mov Temp1, #Pgm_Gov_P_Gain_Decoded; Load proportional gain
  3469. mov A, @Temp1
  3470. mov Temp3, A ; Store in Temp3
  3471. ; Load proportional
  3472. clr C
  3473. mov A, Gov_Proportional_L ; Nominal multiply by 2
  3474. rlc A
  3475. mov Temp1, A
  3476. mov A, Gov_Proportional_H
  3477. rlc A
  3478. mov Temp2, A
  3479. ; Apply gain
  3480. call mult_s16_by_u8_div_16
  3481. ; Check error and limit (to low byte)
  3482. mov A, Temp2
  3483. jnb ACC.7, governor_check_prop_corr_limit_pos ; Check sign bit
  3484. clr C
  3485. mov A, Temp1
  3486. subb A, #80h ; Is error too negative?
  3487. mov A, Temp2
  3488. subb A, #0FFh
  3489. jc governor_limit_prop_corr_neg ; Yes - limit
  3490. ajmp governor_apply_prop_corr
  3491. governor_check_prop_corr_limit_pos:
  3492. clr C
  3493. mov A, Temp1
  3494. subb A, #7Fh ; Is error too positive?
  3495. mov A, Temp2
  3496. subb A, #00h
  3497. jnc governor_limit_prop_corr_pos ; Yes - limit
  3498. ajmp governor_apply_prop_corr
  3499. governor_limit_prop_corr_pos:
  3500. mov Temp1, #7Fh ; Limit to max positive (2's complement)
  3501. mov Temp2, #00h
  3502. ajmp governor_apply_prop_corr
  3503. governor_limit_prop_corr_neg:
  3504. mov Temp1, #80h ; Limit to max negative (2's complement)
  3505. mov Temp2, #0FFh
  3506. governor_apply_prop_corr:
  3507. ; Test proportional sign
  3508. mov A, Temp1
  3509. jb ACC.7, governor_corr_neg_prop ; If proportional negative - go to correct negative
  3510. ; Subtract positive proportional
  3511. clr C
  3512. mov A, Governor_Req_Pwm
  3513. subb A, Temp1
  3514. mov Temp1, A
  3515. ; Check result
  3516. jc governor_corr_prop_min_pwm ; Is result negative?
  3517. clr C
  3518. mov A, Temp1 ; Is result below pwm min?
  3519. subb A, #1
  3520. jc governor_corr_prop_min_pwm ; Yes
  3521. jmp governor_store_prop_corr ; No - store proportional correction
  3522. governor_corr_prop_min_pwm:
  3523. mov Temp1, #1 ; Load minimum pwm
  3524. jmp governor_store_prop_corr
  3525. governor_corr_neg_prop:
  3526. ; Add negative proportional
  3527. mov A, Temp1
  3528. cpl A
  3529. add A, #1
  3530. add A, Governor_Req_Pwm
  3531. mov Temp1, A
  3532. ; Check result
  3533. jc governor_corr_prop_max_pwm ; Is result above max?
  3534. jmp governor_store_prop_corr ; No - store proportional correction
  3535. governor_corr_prop_max_pwm:
  3536. mov Temp1, #255 ; Load maximum pwm
  3537. governor_store_prop_corr:
  3538. ; Store proportional pwm
  3539. mov Gov_Prop_Pwm, Temp1
  3540. calc_governor_prop_corr_exit:
  3541. ret
  3542. ; Fifth governor routine - calculate governor integral correction
  3543. calc_governor_int_correction:
  3544. ; Exit if governor is inactive
  3545. mov A, Gov_Active
  3546. jnz calc_governor_int_corr
  3547. jmp calc_governor_int_corr_exit
  3548. calc_governor_int_corr:
  3549. ; Load integral gain
  3550. mov Temp1, #Pgm_Gov_I_Gain_Decoded; Load integral gain
  3551. mov A, @Temp1
  3552. mov Temp3, A ; Store in Temp3
  3553. ; Load integral
  3554. mov Temp1, Gov_Integral_H
  3555. mov Temp2, Gov_Integral_X
  3556. ; Apply gain
  3557. call mult_s16_by_u8_div_16
  3558. ; Check integral and limit
  3559. mov A, Temp2
  3560. jnb ACC.7, governor_check_int_corr_limit_pos ; Check sign bit
  3561. clr C
  3562. mov A, Temp1
  3563. subb A, #01h ; Is integral too negative?
  3564. mov A, Temp2
  3565. subb A, #0FFh
  3566. jc governor_limit_int_corr_neg ; Yes - limit
  3567. jmp governor_apply_int_corr
  3568. governor_check_int_corr_limit_pos:
  3569. clr C
  3570. mov A, Temp1
  3571. subb A, #0FFh ; Is integral too positive?
  3572. mov A, Temp2
  3573. subb A, #00h
  3574. jnc governor_limit_int_corr_pos ; Yes - limit
  3575. jmp governor_apply_int_corr
  3576. governor_limit_int_corr_pos:
  3577. mov Temp1, #0FFh ; Limit to max positive (2's complement)
  3578. mov Temp2, #00h
  3579. jmp governor_apply_int_corr
  3580. governor_limit_int_corr_neg:
  3581. mov Temp1, #01h ; Limit to max negative (2's complement)
  3582. mov Temp2, #0FFh
  3583. governor_apply_int_corr:
  3584. ; Test integral sign
  3585. mov A, Temp2
  3586. jb ACC.7, governor_corr_neg_int ; If integral negative - go to correct negative
  3587. ; Subtract positive integral
  3588. clr C
  3589. mov A, Gov_Prop_Pwm
  3590. subb A, Temp1
  3591. mov Temp1, A
  3592. ; Check result
  3593. jc governor_corr_int_min_pwm ; Is result negative?
  3594. clr C
  3595. mov A, Temp1 ; Is result below pwm min?
  3596. subb A, #1
  3597. jc governor_corr_int_min_pwm ; Yes
  3598. jmp governor_store_int_corr ; No - store correction
  3599. governor_corr_int_min_pwm:
  3600. mov Temp1, #0 ; Load minimum pwm
  3601. jmp governor_store_int_corr
  3602. governor_corr_neg_int:
  3603. ; Add negative integral
  3604. mov A, Temp1
  3605. cpl A
  3606. add A, #1
  3607. add A, Gov_Prop_Pwm
  3608. mov Temp1, A
  3609. ; Check result
  3610. jc governor_corr_int_max_pwm ; Is result above max?
  3611. jmp governor_store_int_corr ; No - store correction
  3612. governor_corr_int_max_pwm:
  3613. mov Temp1, #255 ; Load maximum pwm
  3614. governor_store_int_corr:
  3615. ; Store current pwm
  3616. mov Current_Pwm, Temp1
  3617. calc_governor_int_corr_exit:
  3618. ret
  3619. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  3620. ;
  3621. ; Set pwm limit low rpm
  3622. ;
  3623. ; No assumptions
  3624. ;
  3625. ; Sets power limit for low rpms and disables demag for low rpms
  3626. ;
  3627. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  3628. set_pwm_limit_low_rpm:
  3629. ; Set pwm limit and demag disable for low rpms
  3630. mov Temp1, #0FFh ; Default full power
  3631. clr Flags0.DEMAG_ENABLED ; Default disabled
  3632. mov A, Flags1
  3633. anl A, #((1 SHL STARTUP_PHASE)+(1 SHL INITIAL_RUN_PHASE))
  3634. jnz set_pwm_limit_low_rpm_exit ; Exit if any startup phase set
  3635. setb Flags0.DEMAG_ENABLED ; Enable demag
  3636. clr C
  3637. mov A, Comm_Period4x_H
  3638. subb A, #0Ah ; ~31250 eRPM
  3639. jc set_pwm_demag_done ; If speed above - branch
  3640. clr C
  3641. mov A, Current_Pwm_Limited
  3642. subb A, #40h ; Do not disable if pwm above 25%
  3643. jnc set_pwm_demag_done
  3644. clr Flags0.DEMAG_ENABLED ; Disable demag
  3645. set_pwm_demag_done:
  3646. mov A, Comm_Period4x_H
  3647. jz set_pwm_limit_low_rpm_exit ; Avoid divide by zero
  3648. mov A, #255 ; Divide 255 by Comm_Period4x_H
  3649. mov B, Comm_Period4x_H
  3650. div AB
  3651. mov B, Low_Rpm_Pwr_Slope ; Multiply by slope
  3652. mul AB
  3653. mov Temp1, A ; Set new limit
  3654. xch A, B
  3655. jz ($+4) ; Limit to max
  3656. mov Temp1, #0FFh
  3657. clr C
  3658. mov A, Temp1 ; Limit to min
  3659. subb A, Pwm_Spoolup_Beg
  3660. jnc set_pwm_limit_low_rpm_exit
  3661. mov Temp1, Pwm_Spoolup_Beg
  3662. set_pwm_limit_low_rpm_exit:
  3663. mov Pwm_Limit_Low_Rpm, Temp1
  3664. ret
  3665. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  3666. ;
  3667. ; Measure lipo cells
  3668. ;
  3669. ; No assumptions
  3670. ;
  3671. ; Measure voltage and calculate lipo cells
  3672. ;
  3673. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  3674. measure_lipo_cells:
  3675. IF MODE == 1 ; Tail
  3676. ; If tail, then exit
  3677. jmp measure_lipo_exit
  3678. ENDIF
  3679. measure_lipo_start:
  3680. ; Load programmed low voltage limit
  3681. mov Temp1, #Pgm_Low_Voltage_Lim ; Load limit
  3682. mov A, @Temp1
  3683. mov Bit_Access, A ; Store in Bit_Access
  3684. ; Set commutation to BpFET on
  3685. call comm5comm6
  3686. ; Start adc
  3687. Start_Adc
  3688. ; Wait for ADC reference to settle, and then start again
  3689. call wait1ms
  3690. Start_Adc
  3691. ; Wait for ADC conversion to complete
  3692. measure_lipo_wait_adc:
  3693. Get_Adc_Status
  3694. jb AD0BUSY, measure_lipo_wait_adc
  3695. ; Read ADC result
  3696. Read_Adc_Result
  3697. ; Stop ADC
  3698. Stop_Adc
  3699. ; Switch power off
  3700. call switch_power_off
  3701. ; Set limit step
  3702. mov Lipo_Adc_Limit_L, #ADC_LIMIT_L
  3703. mov Lipo_Adc_Limit_H, #ADC_LIMIT_H
  3704. clr C
  3705. mov A, #ADC_LIMIT_H ; Divide 3.0V value by 2
  3706. rrc A
  3707. mov Temp6, A
  3708. mov A, #ADC_LIMIT_L
  3709. rrc A
  3710. mov Temp5, A
  3711. mov A, #ADC_LIMIT_L ; Calculate 1.5*3.0V=4.5V value
  3712. add A, Temp5
  3713. mov Temp5, A
  3714. mov A, #ADC_LIMIT_H
  3715. addc A, Temp6
  3716. mov Temp6, A
  3717. mov A, Temp5 ; Copy step
  3718. mov Temp3, A
  3719. mov A, Temp6
  3720. mov Temp4, A
  3721. measure_lipo_cell_loop:
  3722. ; Check voltage against xS lower limit
  3723. clr C
  3724. mov A, Temp1
  3725. subb A, Temp3 ; Voltage above limit?
  3726. mov A, Temp2
  3727. subb A, Temp4
  3728. jc measure_lipo_adjust ; No - branch
  3729. ; Set xS voltage limit
  3730. mov A, Lipo_Adc_Limit_L
  3731. add A, #ADC_LIMIT_L
  3732. mov Lipo_Adc_Limit_L, A
  3733. mov A, Lipo_Adc_Limit_H
  3734. addc A, #ADC_LIMIT_H
  3735. mov Lipo_Adc_Limit_H, A
  3736. ; Set (x+1)S lower limit
  3737. mov A, Temp3
  3738. add A, Temp5 ; Add step
  3739. mov Temp3, A
  3740. mov A, Temp4
  3741. addc A, Temp6
  3742. mov Temp4, A
  3743. jmp measure_lipo_cell_loop ; Check for one more battery cell
  3744. measure_lipo_adjust:
  3745. mov Temp7, Lipo_Adc_Limit_L
  3746. mov Temp8, Lipo_Adc_Limit_H
  3747. ; Calculate 3.125%
  3748. clr C
  3749. mov A, Lipo_Adc_Limit_H
  3750. rrc A
  3751. mov Temp2, A
  3752. mov A, Lipo_Adc_Limit_L
  3753. rrc A
  3754. mov Temp1, A ; After this 50%
  3755. clr C
  3756. mov A, Temp2
  3757. rrc A
  3758. mov Temp2, A
  3759. mov A, Temp1
  3760. rrc A
  3761. mov Temp1, A ; After this 25%
  3762. mov A, Lipo_Adc_Limit_L ; Set adc reference for voltage compensation
  3763. add A, Temp1
  3764. mov Lipo_Adc_Reference_L, A
  3765. mov A, Lipo_Adc_Limit_H
  3766. addc A, Temp2
  3767. mov Lipo_Adc_Reference_H, A
  3768. ; Divide three times to get to 3.125%
  3769. mov Temp3, #3
  3770. measure_lipo_divide_loop:
  3771. clr C
  3772. mov A, Temp2
  3773. rrc A
  3774. mov Temp2, A
  3775. mov A, Temp1
  3776. rrc A
  3777. mov Temp1, A
  3778. djnz Temp3, measure_lipo_divide_loop
  3779. ; Add the programmed number of 0.1V (or 3.125% increments)
  3780. mov Temp3, Bit_Access ; Load programmed limit (Bit_Access has Pgm_Low_Voltage_Lim)
  3781. dec Temp3
  3782. jnz measure_lipo_limit_on ; Is low voltage limiting on?
  3783. mov Lipo_Adc_Limit_L, #0 ; No - set limit to zero
  3784. mov Lipo_Adc_Limit_H, #0
  3785. jmp measure_lipo_exit
  3786. measure_lipo_limit_on:
  3787. dec Temp3
  3788. mov A, Temp3
  3789. jz measure_lipo_update
  3790. measure_lipo_add_loop:
  3791. mov A, Temp7 ; Add 3.125%
  3792. add A, Temp1
  3793. mov Temp7, A
  3794. mov A, Temp8
  3795. addc A, Temp2
  3796. mov Temp8, A
  3797. djnz Temp3, measure_lipo_add_loop
  3798. measure_lipo_update:
  3799. ; Set ADC limit
  3800. mov Lipo_Adc_Limit_L, Temp7
  3801. mov Lipo_Adc_Limit_H, Temp8
  3802. measure_lipo_exit:
  3803. ret
  3804. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  3805. ;
  3806. ; Start ADC conversion
  3807. ;
  3808. ; No assumptions
  3809. ;
  3810. ; Start conversion used for measuring power supply voltage
  3811. ;
  3812. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  3813. start_adc_conversion:
  3814. ; Start adc
  3815. Start_Adc
  3816. ret
  3817. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  3818. ;
  3819. ; Check temperature, power supply voltage and limit power
  3820. ;
  3821. ; No assumptions
  3822. ;
  3823. ; Used to limit main motor power in order to maintain the required voltage
  3824. ;
  3825. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  3826. check_temp_voltage_and_limit_power:
  3827. ; Load programmed low voltage limit
  3828. mov Temp1, #Pgm_Low_Voltage_Lim
  3829. mov A, @Temp1
  3830. mov Temp8, A ; Store in Temp8
  3831. ; Wait for ADC conversion to complete
  3832. Get_Adc_Status
  3833. jb AD0BUSY, check_temp_voltage_and_limit_power
  3834. ; Read ADC result
  3835. Read_Adc_Result
  3836. ; Stop ADC
  3837. Stop_Adc
  3838. inc Adc_Conversion_Cnt ; Increment conversion counter
  3839. clr C
  3840. mov A, Adc_Conversion_Cnt ; Is conversion count equal to temp rate?
  3841. subb A, #TEMP_CHECK_RATE
  3842. jc check_voltage_start ; No - check voltage
  3843. mov Adc_Conversion_Cnt, #0 ; Yes - temperature check. Reset counter
  3844. mov A, Temp2 ; Move ADC MSB to Temp3
  3845. mov Temp3, A
  3846. mov Temp2, #Pgm_Enable_Temp_Prot ; Is temp protection enabled?
  3847. mov A, @Temp2
  3848. jz temp_check_exit ; No - branch
  3849. mov A, Temp3 ; Is temperature reading below 256?
  3850. jnz temp_average_inc_dec ; No - proceed
  3851. mov A, Current_Average_Temp ; Yes - decrement average
  3852. jz temp_average_updated ; Already zero - no change
  3853. jmp temp_average_dec ; Decrement
  3854. temp_average_inc_dec:
  3855. clr C
  3856. mov A, Temp1 ; Check if current temperature is above or below average
  3857. subb A, Current_Average_Temp
  3858. jz temp_average_updated_load_acc ; Equal - no change
  3859. mov A, Current_Average_Temp ; Above - increment average
  3860. jnc temp_average_inc
  3861. jz temp_average_updated ; Below - decrement average if average is not already zero
  3862. temp_average_dec:
  3863. dec A ; Decrement average
  3864. jmp temp_average_updated
  3865. temp_average_inc:
  3866. inc A ; Increment average
  3867. jz temp_average_dec
  3868. jmp temp_average_updated
  3869. temp_average_updated_load_acc:
  3870. mov A, Current_Average_Temp
  3871. temp_average_updated:
  3872. mov Current_Average_Temp, A
  3873. clr C
  3874. subb A, #TEMP_LIMIT ; Is temperature below first limit?
  3875. jc temp_check_exit ; Yes - exit
  3876. mov Pwm_Limit, #192 ; No - limit pwm
  3877. clr C
  3878. subb A, #TEMP_LIMIT_STEP ; Is temperature below second limit
  3879. jc temp_check_exit ; Yes - exit
  3880. mov Pwm_Limit, #128 ; No - limit pwm
  3881. clr C
  3882. subb A, #TEMP_LIMIT_STEP ; Is temperature below third limit
  3883. jc temp_check_exit ; Yes - exit
  3884. mov Pwm_Limit, #64 ; No - limit pwm
  3885. clr C
  3886. subb A, #TEMP_LIMIT_STEP ; Is temperature below final limit
  3887. jc temp_check_exit ; Yes - exit
  3888. mov Pwm_Limit, #0 ; No - limit pwm
  3889. temp_check_exit:
  3890. Set_Adc_Ip_Volt ; Select adc input for next conversion
  3891. ret
  3892. check_voltage_start:
  3893. IF MODE == 0 OR MODE == 2 ; Main or multi
  3894. ; Check if low voltage limiting is enabled
  3895. mov A, Temp8
  3896. clr C
  3897. subb A, #1 ; Is low voltage limit disabled?
  3898. jz check_voltage_good ; Yes - voltage declared good
  3899. ; Check if ADC is saturated
  3900. clr C
  3901. mov A, Temp1
  3902. subb A, #0FFh
  3903. mov A, Temp2
  3904. subb A, #03h
  3905. jnc check_voltage_good ; ADC saturated, can not make judgement
  3906. ; Check voltage against limit
  3907. clr C
  3908. mov A, Temp1
  3909. subb A, Lipo_Adc_Limit_L
  3910. mov A, Temp2
  3911. subb A, Lipo_Adc_Limit_H
  3912. jnc check_voltage_good ; If voltage above limit - branch
  3913. ; Decrease pwm limit
  3914. mov A, Pwm_Limit
  3915. jz check_voltage_lim ; If limit zero - branch
  3916. dec Pwm_Limit ; Decrement limit
  3917. jmp check_voltage_lim
  3918. check_voltage_good:
  3919. ; Increase pwm limit
  3920. mov A, Pwm_Limit
  3921. cpl A
  3922. jz check_voltage_lim ; If limit max - branch
  3923. inc Pwm_Limit ; Increment limit
  3924. IF MODE == 2 ; Multi
  3925. mov Temp1, #Pgm_Direction ; Check if bidirectional operation
  3926. mov A, @Temp1
  3927. cjne A, #3, check_voltage_lim
  3928. mov A, Pwm_Limit
  3929. add A, #4
  3930. jc check_voltage_lim ; If limit max - branch
  3931. mov Pwm_Limit, A ; Increment limit two steps more
  3932. ENDIF
  3933. check_voltage_lim:
  3934. mov Temp1, Pwm_Limit ; Set limit
  3935. clr C
  3936. mov A, Current_Pwm
  3937. subb A, Temp1
  3938. jnc check_voltage_spoolup_lim ; If current pwm above limit - branch and limit
  3939. mov Temp1, Current_Pwm ; Set current pwm (no limiting)
  3940. check_voltage_spoolup_lim:
  3941. ; Slow spoolup
  3942. clr C
  3943. mov A, Temp1
  3944. subb A, Pwm_Limit_Spoolup
  3945. jc check_voltage_exit ; If current pwm below limit - branch
  3946. mov Temp1, Pwm_Limit_Spoolup
  3947. mov A, Pwm_Limit_Spoolup ; Check if spoolup limit is max
  3948. cpl A
  3949. jz check_voltage_exit ; If max - branch
  3950. mov Pwm_Limit, Pwm_Limit_Spoolup ; Set pwm limit to spoolup limit during ramp (to avoid governor integral buildup)
  3951. check_voltage_exit:
  3952. IF MODE == 0 ; Main
  3953. mov Current_Pwm_Limited, Temp1
  3954. ENDIF
  3955. IF MODE == 2 ; Multi
  3956. ; Set current pwm limited if closed loop mode
  3957. mov Temp2, #Pgm_Gov_Mode ; Governor mode?
  3958. cjne @Temp2, #4, check_voltage_set_pwm ; Yes - branch
  3959. ajmp check_voltage_pwm_done
  3960. check_voltage_set_pwm:
  3961. ; Limit pwm for low rpms
  3962. clr C
  3963. mov A, Temp1 ; Check against limit
  3964. subb A, Pwm_Limit_Low_Rpm
  3965. jc ($+4) ; If current pwm below limit - branch
  3966. mov Temp1, Pwm_Limit_Low_Rpm ; Limit pwm
  3967. mov Current_Pwm_Limited, Temp1
  3968. check_voltage_pwm_done:
  3969. ENDIF
  3970. ENDIF
  3971. IF MODE == 1 ; Tail
  3972. ; Increase pwm limit
  3973. mov A, Pwm_Limit
  3974. cpl A
  3975. jz check_voltage_lim ; If limit max - branch
  3976. inc Pwm_Limit ; Increment limit
  3977. check_voltage_lim:
  3978. ENDIF
  3979. ; Set adc mux for next conversion
  3980. mov A, Adc_Conversion_Cnt ; Is next conversion for temperature?
  3981. cjne A, #(TEMP_CHECK_RATE-1), check_voltage_ret
  3982. Set_Adc_Ip_Temp ; Select temp sensor for next conversion
  3983. check_voltage_ret:
  3984. ret
  3985. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  3986. ;
  3987. ; Set startup PWM routine
  3988. ;
  3989. ; Either the SETTLE_PHASE or the STEPPER_PHASE flag must be set
  3990. ;
  3991. ; Used for pwm control during startup
  3992. ;
  3993. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  3994. set_startup_pwm:
  3995. ; Adjust startup power
  3996. mov A, #PWM_START ; Set power
  3997. mov Temp2, #Pgm_Startup_Pwr_Decoded
  3998. mov B, @Temp2
  3999. mul AB
  4000. xch A, B
  4001. mov C, B.7 ; Multiply result by 2 (unity gain is 128)
  4002. rlc A
  4003. mov Temp1, A ; Transfer to Temp1
  4004. clr C
  4005. mov A, Temp1 ; Check against limit
  4006. subb A, Pwm_Limit
  4007. jc startup_pwm_set_pwm ; If pwm below limit - branch
  4008. mov Temp1, Pwm_Limit ; Limit pwm
  4009. startup_pwm_set_pwm:
  4010. ; Set pwm variables
  4011. mov Requested_Pwm, Temp1 ; Update requested pwm
  4012. mov Current_Pwm, Temp1 ; Update current pwm
  4013. mov Current_Pwm_Limited, Temp1 ; Update limited version of current pwm
  4014. mov Pwm_Spoolup_Beg, Temp1 ; Yes - update spoolup beginning pwm (will use PWM_SETTLE or PWM_SETTLE/2)
  4015. ret
  4016. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4017. ;
  4018. ; Initialize all timings routine
  4019. ;
  4020. ; No assumptions
  4021. ;
  4022. ; Part of initialization before motor start
  4023. ;
  4024. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4025. initialize_all_timings:
  4026. mov Comm_Period4x_L, #00h ; Set commutation period registers
  4027. mov Comm_Period4x_H, #7Fh
  4028. ret
  4029. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4030. ;
  4031. ; Calculate next commutation timing routine
  4032. ;
  4033. ; No assumptions
  4034. ;
  4035. ; Called immediately after each commutation
  4036. ; Also sets up timer 3 to wait advance timing
  4037. ; Two entry points are used
  4038. ;
  4039. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4040. calc_next_comm_timing: ; Entry point for run phase
  4041. ; Read commutation time
  4042. mov TMR2CN, #20h ; Timer2 disabled
  4043. mov Temp1, TMR2L ; Load timer value
  4044. mov Temp2, TMR2H
  4045. mov TMR2CN, #24h ; Timer2 enabled
  4046. IF MCU_50MHZ == 1
  4047. clr C
  4048. mov A, Temp2
  4049. rrc A
  4050. mov Temp2, A
  4051. mov A, Temp1
  4052. rrc A
  4053. mov Temp1, A
  4054. ENDIF
  4055. ; Calculate this commutation time
  4056. mov Temp3, Prev_Comm_L
  4057. mov Temp4, Prev_Comm_H
  4058. mov Prev_Comm_L, Temp1 ; Store timestamp as previous commutation
  4059. mov Prev_Comm_H, Temp2
  4060. clr C
  4061. mov A, Temp1
  4062. subb A, Temp3 ; Calculate the new commutation time
  4063. mov Temp1, A
  4064. mov A, Temp2
  4065. subb A, Temp4
  4066. IF MCU_50MHZ == 1
  4067. anl A, #7Fh
  4068. ENDIF
  4069. mov Temp2, A
  4070. ; Calculate new commutation time
  4071. mov Temp3, Comm_Period4x_L ; Comm_Period4x(-l-h) holds the time of 4 commutations
  4072. mov Temp4, Comm_Period4x_H
  4073. mov Temp5, Comm_Period4x_L ; Copy variables
  4074. mov Temp6, Comm_Period4x_H
  4075. mov Temp7, #4 ; Divide Comm_Period4x 4 times as default
  4076. mov Temp8, #2 ; Divide new commutation time 2 times as default
  4077. clr C
  4078. mov A, Temp4
  4079. subb A, #04h
  4080. jc ($+4)
  4081. dec Temp7 ; Reduce averaging time constant for low speeds
  4082. dec Temp8
  4083. clr C
  4084. mov A, Temp4
  4085. subb A, #08h
  4086. jc ($+4)
  4087. dec Temp7 ; Reduce averaging time constant more for even lower speeds
  4088. dec Temp8
  4089. calc_next_comm_avg_period_div:
  4090. clr C
  4091. mov A, Temp6
  4092. rrc A ; Divide by 2
  4093. mov Temp6, A
  4094. mov A, Temp5
  4095. rrc A
  4096. mov Temp5, A
  4097. djnz Temp7, calc_next_comm_avg_period_div
  4098. clr C
  4099. mov A, Temp3
  4100. subb A, Temp5 ; Subtract a fraction
  4101. mov Temp3, A
  4102. mov A, Temp4
  4103. subb A, Temp6
  4104. mov Temp4, A
  4105. mov A, Temp8 ; Divide new time
  4106. jz calc_next_comm_new_period_div_done
  4107. calc_next_comm_new_period_div:
  4108. clr C
  4109. mov A, Temp2
  4110. rrc A ; Divide by 2
  4111. mov Temp2, A
  4112. mov A, Temp1
  4113. rrc A
  4114. mov Temp1, A
  4115. djnz Temp8, calc_next_comm_new_period_div
  4116. calc_next_comm_new_period_div_done:
  4117. mov A, Temp3
  4118. add A, Temp1 ; Add the divided new time
  4119. mov Temp3, A
  4120. mov A, Temp4
  4121. addc A, Temp2
  4122. mov Temp4, A
  4123. mov Comm_Period4x_L, Temp3 ; Store Comm_Period4x_X
  4124. mov Comm_Period4x_H, Temp4
  4125. jc calc_next_comm_slow ; If period larger than 0xffff - go to slow case
  4126. ret
  4127. calc_next_comm_slow:
  4128. mov Comm_Period4x_L, #0FFh ; Set commutation period registers to very slow timing (0xffff)
  4129. mov Comm_Period4x_H, #0FFh
  4130. ret
  4131. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4132. ;
  4133. ; Wait advance timing routine
  4134. ;
  4135. ; No assumptions
  4136. ;
  4137. ; Waits for the advance timing to elapse and sets up the next zero cross wait
  4138. ;
  4139. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4140. wait_advance_timing:
  4141. jnb Flags0.T3_PENDING, ($+5)
  4142. ajmp wait_advance_timing
  4143. ; Setup next wait time
  4144. mov Next_Wt_L, Wt_ZC_Timeout_L
  4145. mov Next_Wt_H, Wt_ZC_Timeout_H
  4146. setb Flags0.T3_PENDING
  4147. orl EIE1, #80h ; Enable timer3 interrupts
  4148. ret
  4149. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4150. ;
  4151. ; Calculate new wait times routine
  4152. ;
  4153. ; No assumptions
  4154. ;
  4155. ; Calculates new wait times
  4156. ;
  4157. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4158. calc_new_wait_times:
  4159. ; Load programmed commutation timing
  4160. mov Temp1, #Pgm_Comm_Timing ; Load timing setting
  4161. mov A, @Temp1
  4162. mov Temp8, A ; Store in Temp8
  4163. clr C
  4164. mov A, Demag_Detected_Metric ; Check demag metric
  4165. subb A, #130
  4166. jc ($+3)
  4167. inc Temp8 ; Increase timing
  4168. clr C
  4169. mov A, Demag_Detected_Metric
  4170. subb A, #160
  4171. jc ($+3)
  4172. inc Temp8 ; Increase timing again
  4173. clr C
  4174. mov A, Temp8 ; Limit timing to max
  4175. subb A, #6
  4176. jc ($+4)
  4177. mov Temp8, #5 ; Set timing to max
  4178. mov Temp7, #(COMM_TIME_RED SHL 1)
  4179. dec Temp7
  4180. jnb Flags2.PGM_PWMOFF_DAMPED, ($+4) ; More reduction for damped
  4181. inc Temp7 ; Increase more
  4182. clr C
  4183. mov A, Comm_Period4x_H ; More reduction for higher rpms
  4184. subb A, #3 ; 104k eRPM
  4185. jnc calc_new_wait_per_low
  4186. inc Temp7 ; Increase
  4187. inc Temp7
  4188. jnb Flags2.PGM_PWMOFF_DAMPED, calc_new_wait_per_low ; More reduction for damped
  4189. inc Temp7 ; Increase more
  4190. calc_new_wait_per_low:
  4191. clr C
  4192. mov A, Comm_Period4x_H ; More reduction for higher rpms
  4193. subb A, #2 ; 156k eRPM
  4194. jnc calc_new_wait_per_high
  4195. inc Temp7 ; Increase more
  4196. inc Temp7
  4197. jnb Flags2.PGM_PWMOFF_DAMPED, calc_new_wait_per_high ; More reduction for damped
  4198. inc Temp7 ; Increase more
  4199. calc_new_wait_per_high:
  4200. ; Load current commutation timing
  4201. mov Temp2, Comm_Period4x_H ; Load Comm_Period4x
  4202. mov Temp1, Comm_Period4x_L
  4203. mov Temp3, #4 ; Divide 4 times
  4204. divide_wait_times:
  4205. clr C
  4206. mov A, Temp2
  4207. rrc A ; Divide by 2
  4208. mov Temp2, A
  4209. mov A, Temp1
  4210. rrc A
  4211. mov Temp1, A
  4212. djnz Temp3, divide_wait_times
  4213. clr C
  4214. mov A, Temp1
  4215. subb A, Temp7
  4216. mov Temp1, A
  4217. mov A, Temp2
  4218. subb A, #0
  4219. mov Temp2, A
  4220. jc load_min_time ; Check that result is still positive
  4221. clr C
  4222. mov A, Temp1
  4223. subb A, #(COMM_TIME_MIN SHL 1)
  4224. mov A, Temp2
  4225. subb A, #0
  4226. jnc adjust_timing ; Check that result is still above minumum
  4227. load_min_time:
  4228. mov Temp1, #(COMM_TIME_MIN SHL 1)
  4229. clr A
  4230. mov Temp2, A
  4231. adjust_timing:
  4232. mov A, Temp2 ; Copy values
  4233. mov Temp4, A
  4234. mov A, Temp1
  4235. mov Temp3, A
  4236. clr C
  4237. mov A, Temp2
  4238. rrc A ; Divide by 2
  4239. mov Temp6, A
  4240. mov A, Temp1
  4241. rrc A
  4242. mov Temp5, A
  4243. mov Wt_Zc_Timeout_L, Temp1 ; Set 15deg time for zero cross scan timeout
  4244. mov Wt_Zc_Timeout_H, Temp2
  4245. clr C
  4246. mov A, Temp8 ; (Temp8 has Pgm_Comm_Timing)
  4247. subb A, #3 ; Is timing normal?
  4248. jz store_times_decrease ; Yes - branch
  4249. mov A, Temp8
  4250. jb ACC.0, adjust_timing_two_steps ; If an odd number - branch
  4251. mov A, Temp1 ; Add 7.5deg and store in Temp1/2
  4252. add A, Temp5
  4253. mov Temp1, A
  4254. mov A, Temp2
  4255. addc A, Temp6
  4256. mov Temp2, A
  4257. mov A, Temp5 ; Store 7.5deg in Temp3/4
  4258. mov Temp3, A
  4259. mov A, Temp6
  4260. mov Temp4, A
  4261. jmp store_times_up_or_down
  4262. adjust_timing_two_steps:
  4263. mov A, Temp1 ; Add 15deg and store in Temp1/2
  4264. add A, Temp1
  4265. mov Temp1, A
  4266. mov A, Temp2
  4267. addc A, Temp2
  4268. mov Temp2, A
  4269. clr C
  4270. mov A, Temp1
  4271. subb A, #(COMM_TIME_MIN SHL 1)
  4272. mov Temp1, A
  4273. mov A, Temp2
  4274. subb A, #0
  4275. mov Temp2, A
  4276. mov Temp3, #(COMM_TIME_MIN SHL 1) ; Store minimum time in Temp3/4
  4277. clr A
  4278. mov Temp4, A
  4279. store_times_up_or_down:
  4280. clr C
  4281. mov A, Temp8
  4282. subb A, #3 ; Is timing higher than normal?
  4283. jc store_times_decrease ; No - branch
  4284. store_times_increase:
  4285. mov Wt_Comm_L, Temp3 ; Now commutation time (~60deg) divided by 4 (~15deg nominal)
  4286. mov Wt_Comm_H, Temp4
  4287. mov Wt_Advance_L, Temp1 ; New commutation advance time (~15deg nominal)
  4288. mov Wt_Advance_H, Temp2
  4289. mov Wt_Zc_Scan_L, Temp5 ; Use this value for zero cross scan delay (7.5deg)
  4290. mov Wt_Zc_Scan_H, Temp6
  4291. ret
  4292. store_times_decrease:
  4293. mov Wt_Comm_L, Temp1 ; Now commutation time (~60deg) divided by 4 (~15deg nominal)
  4294. mov Wt_Comm_H, Temp2
  4295. mov Wt_Advance_L, Temp3 ; New commutation advance time (~15deg nominal)
  4296. mov Wt_Advance_H, Temp4
  4297. mov Wt_Zc_Scan_L, Temp5 ; Use this value for zero cross scan delay (7.5deg)
  4298. mov Wt_Zc_Scan_H, Temp6
  4299. ret
  4300. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4301. ;
  4302. ; Wait before zero cross scan routine
  4303. ;
  4304. ; No assumptions
  4305. ;
  4306. ; Waits for the zero cross scan wait time to elapse
  4307. ; Also sets up timer 3 for the zero cross scan timeout time
  4308. ;
  4309. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4310. wait_before_zc_scan:
  4311. jnb Flags0.T3_PENDING, ($+5)
  4312. ajmp wait_before_zc_scan
  4313. setb Flags0.T3_PENDING
  4314. orl EIE1, #80h ; Enable timer3 interrupts
  4315. mov A, Flags1
  4316. anl A, #((1 SHL STARTUP_PHASE)+(1 SHL INITIAL_RUN_PHASE))
  4317. jz wait_before_zc_exit
  4318. mov Temp1, Comm_Period4x_L ; Set long timeout when starting
  4319. mov Temp2, Comm_Period4x_H
  4320. ; Break deadlock cyclic patterns during startup
  4321. mov A, Startup_Ok_Cnt
  4322. subb A, #8
  4323. jnc wait_before_zc_random_done
  4324. mov A, Temp1
  4325. jb ACC.0, wait_before_zc_random_done ; Use LSB as a random number
  4326. mov Temp2, Wt_Zc_Timeout_H
  4327. wait_before_zc_random_done:
  4328. IF MCU_50MHZ == 1
  4329. clr C
  4330. mov A, Temp1
  4331. rlc A
  4332. mov Temp1, A
  4333. mov A, Temp2
  4334. rlc A
  4335. mov Temp2, A
  4336. ENDIF
  4337. mov TMR3CN, #00h ; Timer3 disabled
  4338. clr C
  4339. clr A
  4340. subb A, Temp1 ; Set timeout
  4341. mov TMR3L, A
  4342. clr A
  4343. subb A, Temp2
  4344. mov TMR3H, A
  4345. mov TMR3CN, #04h ; Timer3 enabled
  4346. setb Flags0.T3_PENDING
  4347. anl TMR3CN, #07Fh ; Clear interrupt flag
  4348. orl EIE1, #80h ; Enable timer3 interrupts
  4349. wait_before_zc_exit:
  4350. ret
  4351. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4352. ;
  4353. ; Wait for comparator to go low/high routines
  4354. ;
  4355. ; No assumptions
  4356. ;
  4357. ; Waits for the zero cross scan wait time to elapse
  4358. ; Then scans for comparator going low/high
  4359. ;
  4360. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4361. wait_for_comp_out_low:
  4362. setb Flags0.DEMAG_DETECTED ; Set demag detected flag as default
  4363. mov Comparator_Read_Cnt, #0 ; Reset number of comparator reads
  4364. mov Bit_Access, #00h ; Desired comparator output
  4365. jmp wait_for_comp_out_start
  4366. wait_for_comp_out_high:
  4367. setb Flags0.DEMAG_DETECTED ; Set demag detected flag as default
  4368. mov Comparator_Read_Cnt, #0 ; Reset number of comparator reads
  4369. mov Bit_Access, #40h ; Desired comparator output
  4370. wait_for_comp_out_start:
  4371. mov A, Flags1 ; Clear demag detected flag if start phases
  4372. anl A, #((1 SHL STARTUP_PHASE)+(1 SHL INITIAL_RUN_PHASE))
  4373. jz ($+4)
  4374. clr Flags0.DEMAG_DETECTED
  4375. setb EA ; Enable interrupts
  4376. jb Flags0.T3_PENDING, wait_for_comp_out_not_timed_out; Has zero cross scan timeout elapsed?
  4377. mov A, Comparator_Read_Cnt ; Check that comparator has been read
  4378. jz wait_for_comp_out_not_timed_out ; If not read - branch
  4379. ret ; Return
  4380. wait_for_comp_out_not_timed_out:
  4381. ; Set number of comparator readings
  4382. mov Temp1, #1 ; Number of OK readings required
  4383. mov Temp3, #2 ; Number of fast consecutive readings
  4384. clr C ; Set number of readings higher for lower speeds
  4385. mov A, Comm_Period4x_H
  4386. subb A, #05h
  4387. jc ($+4)
  4388. mov Temp1, #2
  4389. clr C
  4390. mov A, Comm_Period4x_H
  4391. subb A, #0Ah
  4392. jc ($+4)
  4393. mov Temp1, #3
  4394. clr C ; Set number of consecutive readings higher for lower speeds
  4395. mov A, Comm_Period4x_H
  4396. subb A, #0Fh
  4397. jc ($+4)
  4398. mov Temp3, #3
  4399. jnb Flags1.STARTUP_PHASE, comp_wait_on_comp_able ; Set many samples during startup
  4400. mov Temp1, #30
  4401. mov Temp3, #1
  4402. comp_wait_on_comp_able:
  4403. jb Flags0.T3_PENDING, comp_wait_on_comp_able_not_timed_out ; Has zero cross scan timeout elapsed?
  4404. mov A, Comparator_Read_Cnt ; Check that comparator has been read
  4405. jz comp_wait_on_comp_able_not_timed_out ; If not read - branch
  4406. setb EA ; Enable interrupts
  4407. ret ; Yes - return
  4408. comp_wait_on_comp_able_not_timed_out:
  4409. setb EA ; Enable interrupts
  4410. nop ; Allocate only just enough time to capture interrupt
  4411. nop
  4412. clr EA ; Disable interrupts
  4413. clr C
  4414. mov A, Comm_Period4x_H ; Reduce required distance to pwm transition for higher speeds
  4415. mov Temp4, A
  4416. subb A, #0Fh
  4417. jc ($+4)
  4418. mov Temp4, #0Fh
  4419. mov A, Temp4
  4420. inc A
  4421. jnb Flags2.PGM_PWM_HIGH_FREQ, ($+4) ; More delay for high pwm frequency
  4422. rl A
  4423. jb Flags0.PWM_ON, ($+4) ; More delay for pwm off
  4424. rl A
  4425. mov Temp2, A
  4426. jnb Flags1.STARTUP_PHASE, ($+5) ; Set a long delay from pwm on/off events during startup
  4427. mov Temp2, #130
  4428. IF MCU_50MHZ == 0
  4429. mov A, TL1
  4430. ELSE
  4431. mov A, TH1
  4432. rrc A
  4433. mov A, TL1
  4434. rrc A
  4435. ENDIF
  4436. clr C
  4437. subb A, Temp2
  4438. jc comp_wait_on_comp_able ; Re-evaluate pwm cycle
  4439. inc Comparator_Read_Cnt ; Increment comparator read count
  4440. mov A, Temp3
  4441. mov Temp4, A
  4442. read_comp_loop:
  4443. Read_Comp_Out ; Read comparator output
  4444. anl A, #40h
  4445. cjne A, Bit_Access, comp_read_wrong
  4446. djnz Temp4, read_comp_loop ; Decrement readings count
  4447. ajmp comp_read_ok
  4448. comp_read_wrong:
  4449. jb Flags0.DEMAG_DETECTED, ($+5)
  4450. ajmp wait_for_comp_out_start ; If comparator output is not correct, and timeout already extended - go back and restart
  4451. clr Flags0.DEMAG_DETECTED ; Clear demag detected flag
  4452. mov TMR3CN, #00h ; Timer3 disabled
  4453. mov Temp7, Comm_Period4x_L ; Set timeout to comm period 4x value
  4454. mov Temp8, Comm_Period4x_H
  4455. IF MCU_50MHZ == 1
  4456. clr C
  4457. mov A, Temp7
  4458. rlc A
  4459. mov Temp7, A
  4460. mov A, Temp8
  4461. rlc A
  4462. mov Temp8, A
  4463. ENDIF
  4464. clr C
  4465. clr A
  4466. subb A, Temp7
  4467. mov TMR3L, A
  4468. clr A
  4469. subb A, Temp8
  4470. mov TMR3H, A
  4471. mov TMR3CN, #04h ; Timer3 enabled
  4472. setb Flags0.T3_PENDING
  4473. anl TMR3CN, #07Fh ; Clear interrupt flag in case there are pending interrupts
  4474. orl EIE1, #80h ; Enable timer3 interrupts
  4475. ajmp wait_for_comp_out_start ; If comparator output is not correct - go back and restart
  4476. comp_read_ok:
  4477. jnb Flags0.DEMAG_DETECTED, ($+5) ; Do not accept correct comparator output if it is demag
  4478. ajmp wait_for_comp_out_start
  4479. djnz Temp1, comp_wait_on_comp_able ; Decrement readings counter - repeat comparator reading if not zero
  4480. setb EA ; Enable interrupts
  4481. ret
  4482. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4483. ;
  4484. ; Evaluate comparator integrity
  4485. ;
  4486. ; No assumptions
  4487. ;
  4488. ; Checks comparator signal behaviour versus expected behaviour
  4489. ;
  4490. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4491. evaluate_comparator_integrity:
  4492. jnb Flags1.STARTUP_PHASE, eval_comp_check_timeout
  4493. inc Startup_Ok_Cnt ; Increment ok counter
  4494. jb Flags0.T3_PENDING, eval_comp_exit
  4495. mov Startup_Ok_Cnt, #0 ; Reset ok counter
  4496. jmp eval_comp_exit
  4497. eval_comp_check_timeout:
  4498. jb Flags0.T3_PENDING, eval_comp_exit ; Has timeout elapsed?
  4499. jb Flags0.DEMAG_DETECTED, eval_comp_exit ; Do not exit run mode if it is a demag situation
  4500. jb Flags1.DIR_CHANGE_BRAKE, eval_comp_exit ; Do not exit run mode if it is a direction change brake
  4501. dec SP ; Routine exit without "ret" command
  4502. dec SP
  4503. ljmp run_to_wait_for_power_on ; Yes - exit run mode
  4504. eval_comp_exit:
  4505. ret
  4506. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4507. ;
  4508. ; Setup commutation timing routine
  4509. ;
  4510. ; No assumptions
  4511. ;
  4512. ; Sets up and starts wait from commutation to zero cross
  4513. ;
  4514. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4515. setup_comm_wait:
  4516. mov Temp1, Wt_Comm_L ; Set wait commutation value
  4517. mov Temp2, Wt_Comm_H
  4518. IF MCU_50MHZ == 1
  4519. clr C
  4520. mov A, Temp1
  4521. rlc A
  4522. mov Temp1, A
  4523. mov A, Temp2
  4524. rlc A
  4525. mov Temp2, A
  4526. ENDIF
  4527. mov TMR3CN, #00h ; Timer3 disabled
  4528. anl TMR3CN, #07Fh ; Clear interrupt flag
  4529. clr C
  4530. clr A
  4531. subb A, Temp1
  4532. mov TMR3L, A
  4533. clr A
  4534. subb A, Temp2
  4535. mov TMR3H, A
  4536. mov TMR3CN, #04h ; Timer3 enabled
  4537. ; Setup next wait time
  4538. mov Next_Wt_L, Wt_Advance_L
  4539. mov Next_Wt_H, Wt_Advance_H
  4540. setb Flags0.T3_PENDING
  4541. orl EIE1, #80h ; Enable timer3 interrupts
  4542. ret
  4543. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4544. ;
  4545. ; Wait for commutation routine
  4546. ;
  4547. ; No assumptions
  4548. ;
  4549. ; Waits from zero cross to commutation
  4550. ;
  4551. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4552. wait_for_comm:
  4553. ; Update demag metric
  4554. mov Temp1, #0
  4555. jnb Flags0.DEMAG_ENABLED, ($+8); If demag disabled - branch
  4556. jnb Flags0.DEMAG_DETECTED, ($+5)
  4557. mov Temp1, #1
  4558. mov A, Demag_Detected_Metric ; Sliding average of 8, 256 when demag and 0 when not. Limited to minimum 120
  4559. mov B, #7
  4560. mul AB ; Multiply by 7
  4561. mov Temp2, A
  4562. mov A, B ; Add new value for current demag status
  4563. add A, Temp1
  4564. mov B, A
  4565. mov A, Temp2
  4566. mov C, B.0 ; Divide by 8
  4567. rrc A
  4568. mov C, B.1
  4569. rrc A
  4570. mov C, B.2
  4571. rrc A
  4572. mov Demag_Detected_Metric, A
  4573. clr C
  4574. subb A, #120 ; Limit to minimum 120
  4575. jnc ($+5)
  4576. mov Demag_Detected_Metric, #120
  4577. clr C
  4578. mov A, Demag_Detected_Metric ; Check demag metric
  4579. subb A, Demag_Pwr_Off_Thresh
  4580. jc wait_for_comm_wait ; Cut power if many consecutive demags. This will help retain sync during hard accelerations
  4581. setb Flags0.DEMAG_CUT_POWER ; Set demag power cut flag
  4582. All_nFETs_off
  4583. wait_for_comm_wait:
  4584. jnb Flags0.T3_PENDING, ($+5)
  4585. ajmp wait_for_comm_wait
  4586. ; Setup next wait time
  4587. mov Next_Wt_L, Wt_Zc_Scan_L
  4588. mov Next_Wt_H, Wt_Zc_Scan_H
  4589. setb Flags0.T3_PENDING
  4590. orl EIE1, #80h ; Enable timer3 interrupts
  4591. ret
  4592. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4593. ;
  4594. ; Commutation routines
  4595. ;
  4596. ; No assumptions
  4597. ;
  4598. ; Performs commutation switching
  4599. ; Damped routines uses all pfets on when in pwm off to dampen the motor
  4600. ;
  4601. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4602. comm1comm2:
  4603. Set_RPM_Out
  4604. clr EA ; Disable all interrupts
  4605. All_pFETs_off ; All pfets off
  4606. jnb Flags2.PGM_PWMOFF_DAMPED, comm12_nondamp
  4607. mov DPTR, #pwm_cnfet_apfet_on
  4608. mov A, #NFETON_DELAY ; Delay
  4609. djnz ACC, $
  4610. jmp comm12_prech_done ; Do not do precharge when running damped
  4611. comm12_nondamp:
  4612. IF HIGH_DRIVER_PRECHG_TIME NE 0 ; Precharge high side gate driver
  4613. mov A, Comm_Period4x_H
  4614. anl A, #0F8h ; Check if comm period is less than 8
  4615. jz comm12_prech_done
  4616. AnFET_on
  4617. mov A, #HIGH_DRIVER_PRECHG_TIME
  4618. djnz ACC, $
  4619. AnFET_off
  4620. mov A, #PFETON_DELAY
  4621. djnz ACC, $
  4622. ENDIF
  4623. comm12_prech_done:
  4624. ApFET_on ; Ap on
  4625. Set_Comp_Phase_B ; Set comparator to phase B
  4626. mov Comm_Phase, #2
  4627. jmp comm_exit
  4628. comm2comm3:
  4629. Clear_RPM_Out
  4630. clr EA ; Disable all interrupts
  4631. CnFET_off ; Cn off
  4632. jnb Flags2.PGM_PWMOFF_DAMPED, comm23_nondamp
  4633. mov DPTR, #pwm_bnfet_apfet_on
  4634. BpFET_off
  4635. CpFET_off
  4636. mov A, #NFETON_DELAY ; Delay
  4637. djnz ACC, $
  4638. jmp comm23_nfet
  4639. comm23_nondamp:
  4640. mov DPTR, #pwm_bfet_on
  4641. comm23_nfet:
  4642. jnb Flags0.PWM_ON, comm23_cp ; Is pwm on?
  4643. BnFET_on ; Yes - Bn on
  4644. comm23_cp:
  4645. Set_Comp_Phase_C ; Set comparator to phase C
  4646. mov Comm_Phase, #3
  4647. jmp comm_exit
  4648. comm3comm4:
  4649. clr EA ; Disable all interrupts
  4650. All_pFETs_off ; All pfets off
  4651. jnb Flags2.PGM_PWMOFF_DAMPED, comm34_nondamp
  4652. mov DPTR, #pwm_bnfet_cpfet_on
  4653. mov A, #NFETON_DELAY ; Delay
  4654. djnz ACC, $
  4655. jmp comm34_prech_done ; Do not do precharge when running damped
  4656. comm34_nondamp:
  4657. IF HIGH_DRIVER_PRECHG_TIME NE 0 ; Precharge high side gate driver
  4658. mov A, Comm_Period4x_H
  4659. anl A, #0F8h ; Check if comm period is less than 8
  4660. jz comm34_prech_done
  4661. CnFET_on
  4662. mov A, #HIGH_DRIVER_PRECHG_TIME
  4663. djnz ACC, $
  4664. CnFET_off
  4665. mov A, #PFETON_DELAY
  4666. djnz ACC, $
  4667. ENDIF
  4668. comm34_prech_done:
  4669. CpFET_on ; Cp on
  4670. Set_Comp_Phase_A ; Set comparator to phase A
  4671. mov Comm_Phase, #4
  4672. jmp comm_exit
  4673. comm4comm5:
  4674. clr EA ; Disable all interrupts
  4675. BnFET_off ; Bn off
  4676. jnb Flags2.PGM_PWMOFF_DAMPED, comm45_nondamp
  4677. mov DPTR, #pwm_anfet_cpfet_on
  4678. ApFET_off
  4679. BpFET_off
  4680. mov A, #NFETON_DELAY ; Delay
  4681. djnz ACC, $
  4682. jmp comm45_nfet
  4683. comm45_nondamp:
  4684. mov DPTR, #pwm_afet_on
  4685. comm45_nfet:
  4686. jnb Flags0.PWM_ON, comm45_cp ; Is pwm on?
  4687. AnFET_on ; Yes - An on
  4688. comm45_cp:
  4689. Set_Comp_Phase_B ; Set comparator to phase B
  4690. mov Comm_Phase, #5
  4691. jmp comm_exit
  4692. comm5comm6:
  4693. clr EA ; Disable all interrupts
  4694. All_pFETs_off ; All pfets off
  4695. jnb Flags2.PGM_PWMOFF_DAMPED, comm56_nondamp
  4696. mov DPTR, #pwm_anfet_bpfet_on
  4697. mov A, #NFETON_DELAY ; Delay
  4698. djnz ACC, $
  4699. jmp comm56_prech_done ; Do not do precharge when running damped
  4700. comm56_nondamp:
  4701. IF HIGH_DRIVER_PRECHG_TIME NE 0 ; Precharge high side gate driver
  4702. mov A, Comm_Period4x_H
  4703. anl A, #0F8h ; Check if comm period is less than 8
  4704. jz comm56_prech_done
  4705. BnFET_on
  4706. mov A, #HIGH_DRIVER_PRECHG_TIME
  4707. djnz ACC, $
  4708. BnFET_off
  4709. mov A, #PFETON_DELAY
  4710. djnz ACC, $
  4711. ENDIF
  4712. comm56_prech_done:
  4713. BpFET_on ; Bp on
  4714. Set_Comp_Phase_C ; Set comparator to phase C
  4715. mov Comm_Phase, #6
  4716. jmp comm_exit
  4717. comm6comm1:
  4718. clr EA ; Disable all interrupts
  4719. AnFET_off ; An off
  4720. jnb Flags2.PGM_PWMOFF_DAMPED, comm61_nondamp
  4721. mov DPTR, #pwm_cnfet_bpfet_on
  4722. ApFET_off
  4723. CpFET_off
  4724. mov A, #NFETON_DELAY ; Delay
  4725. djnz ACC, $
  4726. jmp comm61_nfet
  4727. comm61_nondamp:
  4728. mov DPTR, #pwm_cfet_on
  4729. comm61_nfet:
  4730. jnb Flags0.PWM_ON, comm61_cp ; Is pwm on?
  4731. CnFET_on ; Yes - Cn on
  4732. comm61_cp:
  4733. Set_Comp_Phase_A ; Set comparator to phase A
  4734. mov Comm_Phase, #1
  4735. comm_exit:
  4736. IF MODE >= 1 ; Tail or multi
  4737. jnb Flags1.DIR_CHANGE_BRAKE, comm_dir_change_done ; Is it a direction change?
  4738. call switch_power_off ; Switch off power
  4739. mov A, #NFETON_DELAY ; Delay
  4740. djnz ACC, $
  4741. mov A, #PFETON_DELAY ; Delay
  4742. djnz ACC, $
  4743. All_pFETs_on ; All pfets on - Break
  4744. comm_dir_change_done:
  4745. ENDIF
  4746. clr Flags0.DEMAG_CUT_POWER ; Clear demag power cut flag
  4747. setb EA ; Enable all interrupts
  4748. ret
  4749. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4750. ;
  4751. ; Switch power off routine
  4752. ;
  4753. ; No assumptions
  4754. ;
  4755. ; Switches all fets off
  4756. ;
  4757. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4758. switch_power_off:
  4759. mov DPTR, #pwm_nofet_on ; Set DPTR register to pwm_nofet_on label
  4760. All_nFETs_Off ; Turn off all nfets
  4761. All_pFETs_Off ; Turn off all pfets
  4762. clr Flags0.PWM_ON ; Set pwm cycle to pwm off
  4763. ret
  4764. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4765. ;
  4766. ; Set default parameters
  4767. ;
  4768. ; No assumptions
  4769. ;
  4770. ; Sets default programming parameters
  4771. ;
  4772. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4773. set_default_parameters:
  4774. IF MODE == 0 ; Main
  4775. mov Temp1, #Pgm_Gov_P_Gain
  4776. mov @Temp1, #DEFAULT_PGM_MAIN_P_GAIN
  4777. inc Temp1
  4778. mov @Temp1, #DEFAULT_PGM_MAIN_I_GAIN
  4779. inc Temp1
  4780. mov @Temp1, #DEFAULT_PGM_MAIN_GOVERNOR_MODE
  4781. inc Temp1
  4782. mov @Temp1, #DEFAULT_PGM_MAIN_LOW_VOLTAGE_LIM
  4783. inc Temp1
  4784. mov @Temp1, #0FFh ; Motor gain
  4785. inc Temp1
  4786. mov @Temp1, #0FFh ; Motor idle
  4787. inc Temp1
  4788. mov @Temp1, #DEFAULT_PGM_MAIN_STARTUP_PWR
  4789. inc Temp1
  4790. mov @Temp1, #DEFAULT_PGM_MAIN_PWM_FREQ
  4791. inc Temp1
  4792. mov @Temp1, #DEFAULT_PGM_MAIN_DIRECTION
  4793. inc Temp1
  4794. mov @Temp1, #DEFAULT_PGM_MAIN_RCP_PWM_POL
  4795. mov Temp1, #Pgm_Enable_TX_Program
  4796. mov @Temp1, #DEFAULT_PGM_ENABLE_TX_PROGRAM
  4797. inc Temp1
  4798. mov @Temp1, #DEFAULT_PGM_MAIN_REARM_START
  4799. inc Temp1
  4800. mov @Temp1, #DEFAULT_PGM_MAIN_GOV_SETUP_TARGET
  4801. inc Temp1
  4802. mov @Temp1, #0FFh ; Startup rpm
  4803. inc Temp1
  4804. mov @Temp1, #0FFh ; Startup accel
  4805. inc Temp1
  4806. mov @Temp1, #0FFh ; Voltage comp
  4807. inc Temp1
  4808. mov @Temp1, #DEFAULT_PGM_MAIN_COMM_TIMING
  4809. inc Temp1
  4810. mov @Temp1, #0FFh ; Damping force
  4811. inc Temp1
  4812. mov @Temp1, #DEFAULT_PGM_MAIN_GOVERNOR_RANGE
  4813. inc Temp1
  4814. mov @Temp1, #0FFh ; Startup method
  4815. inc Temp1
  4816. mov @Temp1, #DEFAULT_PGM_PPM_MIN_THROTTLE
  4817. inc Temp1
  4818. mov @Temp1, #DEFAULT_PGM_PPM_MAX_THROTTLE
  4819. inc Temp1
  4820. mov @Temp1, #DEFAULT_PGM_MAIN_BEEP_STRENGTH
  4821. inc Temp1
  4822. mov @Temp1, #DEFAULT_PGM_MAIN_BEACON_STRENGTH
  4823. inc Temp1
  4824. mov @Temp1, #DEFAULT_PGM_MAIN_BEACON_DELAY
  4825. inc Temp1
  4826. mov @Temp1, #0FFh ; Throttle rate
  4827. inc Temp1
  4828. mov @Temp1, #DEFAULT_PGM_MAIN_DEMAG_COMP
  4829. inc Temp1
  4830. mov @Temp1, #DEFAULT_PGM_BEC_VOLTAGE_HIGH
  4831. inc Temp1
  4832. mov @Temp1, #DEFAULT_PGM_PPM_CENTER_THROTTLE
  4833. inc Temp1
  4834. mov @Temp1, #DEFAULT_PGM_MAIN_SPOOLUP_TIME
  4835. inc Temp1
  4836. mov @Temp1, #DEFAULT_PGM_ENABLE_TEMP_PROT
  4837. ENDIF
  4838. IF MODE == 1 ; Tail
  4839. mov Temp1, #Pgm_Gov_P_Gain
  4840. mov @Temp1, #0FFh
  4841. inc Temp1
  4842. mov @Temp1, #0FFh ; Governor I gain
  4843. inc Temp1
  4844. mov @Temp1, #0FFh ; Governor mode
  4845. inc Temp1
  4846. mov @Temp1, #0FFh ; Low voltage limit
  4847. inc Temp1
  4848. mov @Temp1, #DEFAULT_PGM_TAIL_GAIN
  4849. inc Temp1
  4850. mov @Temp1, #DEFAULT_PGM_TAIL_IDLE_SPEED
  4851. inc Temp1
  4852. mov @Temp1, #DEFAULT_PGM_TAIL_STARTUP_PWR
  4853. inc Temp1
  4854. mov @Temp1, #DEFAULT_PGM_TAIL_PWM_FREQ
  4855. inc Temp1
  4856. mov @Temp1, #DEFAULT_PGM_TAIL_DIRECTION
  4857. inc Temp1
  4858. mov @Temp1, #DEFAULT_PGM_TAIL_RCP_PWM_POL
  4859. mov Temp1, #Pgm_Enable_TX_Program
  4860. mov @Temp1, #DEFAULT_PGM_ENABLE_TX_PROGRAM
  4861. inc Temp1
  4862. mov @Temp1, #0FFh ; Main rearm start
  4863. inc Temp1
  4864. mov @Temp1, #0FFh ; Governor setup target
  4865. inc Temp1
  4866. mov @Temp1, #0FFh ; Startup rpm
  4867. inc Temp1
  4868. mov @Temp1, #0FFh ; Startup accel
  4869. inc Temp1
  4870. mov @Temp1, #0FFh ; Voltage comp
  4871. inc Temp1
  4872. mov @Temp1, #DEFAULT_PGM_TAIL_COMM_TIMING
  4873. inc Temp1
  4874. mov @Temp1, #0FFh ; Damping force
  4875. inc Temp1
  4876. mov @Temp1, #0FFh ; Governor range
  4877. inc Temp1
  4878. mov @Temp1, #0FFh ; Startup method
  4879. inc Temp1
  4880. mov @Temp1, #DEFAULT_PGM_PPM_MIN_THROTTLE
  4881. inc Temp1
  4882. mov @Temp1, #DEFAULT_PGM_PPM_MAX_THROTTLE
  4883. inc Temp1
  4884. mov @Temp1, #DEFAULT_PGM_TAIL_BEEP_STRENGTH
  4885. inc Temp1
  4886. mov @Temp1, #DEFAULT_PGM_TAIL_BEACON_STRENGTH
  4887. inc Temp1
  4888. mov @Temp1, #DEFAULT_PGM_TAIL_BEACON_DELAY
  4889. inc Temp1
  4890. mov @Temp1, #0FFh ; Throttle rate
  4891. inc Temp1
  4892. mov @Temp1, #DEFAULT_PGM_TAIL_DEMAG_COMP
  4893. inc Temp1
  4894. mov @Temp1, #DEFAULT_PGM_BEC_VOLTAGE_HIGH
  4895. inc Temp1
  4896. mov @Temp1, #DEFAULT_PGM_PPM_CENTER_THROTTLE
  4897. inc Temp1
  4898. mov @Temp1, #0FFh
  4899. inc Temp1
  4900. mov @Temp1, #DEFAULT_PGM_ENABLE_TEMP_PROT
  4901. ENDIF
  4902. IF MODE == 2 ; Multi
  4903. mov Temp1, #Pgm_Gov_P_Gain
  4904. mov @Temp1, #DEFAULT_PGM_MULTI_P_GAIN
  4905. inc Temp1
  4906. mov @Temp1, #DEFAULT_PGM_MULTI_I_GAIN
  4907. inc Temp1
  4908. mov @Temp1, #DEFAULT_PGM_MULTI_GOVERNOR_MODE
  4909. inc Temp1
  4910. mov @Temp1, #DEFAULT_PGM_MULTI_LOW_VOLTAGE_LIM
  4911. inc Temp1
  4912. mov @Temp1, #DEFAULT_PGM_MULTI_GAIN
  4913. inc Temp1
  4914. mov @Temp1, #0FFh
  4915. inc Temp1
  4916. mov @Temp1, #DEFAULT_PGM_MULTI_STARTUP_PWR
  4917. inc Temp1
  4918. mov @Temp1, #DEFAULT_PGM_MULTI_PWM_FREQ
  4919. inc Temp1
  4920. mov @Temp1, #DEFAULT_PGM_MULTI_DIRECTION
  4921. inc Temp1
  4922. mov @Temp1, #DEFAULT_PGM_MULTI_RCP_PWM_POL
  4923. mov Temp1, #Pgm_Enable_TX_Program
  4924. mov @Temp1, #DEFAULT_PGM_ENABLE_TX_PROGRAM
  4925. inc Temp1
  4926. mov @Temp1, #0FFh ; Main rearm start
  4927. inc Temp1
  4928. mov @Temp1, #0FFh ; Governor setup target
  4929. inc Temp1
  4930. mov @Temp1, #0FFh ; Startup rpm
  4931. inc Temp1
  4932. mov @Temp1, #0FFh ; Startup accel
  4933. inc Temp1
  4934. mov @Temp1, #0FFh ; Voltage comp
  4935. inc Temp1
  4936. mov @Temp1, #DEFAULT_PGM_MULTI_COMM_TIMING
  4937. inc Temp1
  4938. mov @Temp1, #0FFh ; Damping force
  4939. inc Temp1
  4940. mov @Temp1, #0FFh ; Governor range
  4941. inc Temp1
  4942. mov @Temp1, #0FFh ; Startup method
  4943. inc Temp1
  4944. mov @Temp1, #DEFAULT_PGM_PPM_MIN_THROTTLE
  4945. inc Temp1
  4946. mov @Temp1, #DEFAULT_PGM_PPM_MAX_THROTTLE
  4947. inc Temp1
  4948. mov @Temp1, #DEFAULT_PGM_MULTI_BEEP_STRENGTH
  4949. inc Temp1
  4950. mov @Temp1, #DEFAULT_PGM_MULTI_BEACON_STRENGTH
  4951. inc Temp1
  4952. mov @Temp1, #DEFAULT_PGM_MULTI_BEACON_DELAY
  4953. inc Temp1
  4954. mov @Temp1, #0FFh ; Throttle rate
  4955. inc Temp1
  4956. mov @Temp1, #DEFAULT_PGM_MULTI_DEMAG_COMP
  4957. inc Temp1
  4958. mov @Temp1, #DEFAULT_PGM_BEC_VOLTAGE_HIGH
  4959. inc Temp1
  4960. mov @Temp1, #DEFAULT_PGM_PPM_CENTER_THROTTLE
  4961. inc Temp1
  4962. mov @Temp1, #0FFh
  4963. inc Temp1
  4964. mov @Temp1, #DEFAULT_PGM_ENABLE_TEMP_PROT
  4965. ENDIF
  4966. ret
  4967. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4968. ;
  4969. ; Decode parameters
  4970. ;
  4971. ; No assumptions
  4972. ;
  4973. ; Decodes programming parameters
  4974. ;
  4975. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4976. decode_parameters:
  4977. ; Load programmed pwm frequency
  4978. mov Temp1, #Pgm_Pwm_Freq ; Load pwm freq
  4979. mov A, @Temp1
  4980. mov Temp8, A ; Store in Temp8
  4981. clr Flags2.PGM_PWMOFF_DAMPED
  4982. IF DAMPED_MODE_ENABLE == 1
  4983. cjne Temp8, #3, ($+5)
  4984. setb Flags2.PGM_PWMOFF_DAMPED
  4985. ENDIF
  4986. ; Load programmed direction
  4987. mov Temp1, #Pgm_Direction
  4988. IF MODE >= 1 ; Tail or multi
  4989. mov A, @Temp1
  4990. clr C
  4991. subb A, #3
  4992. jz decode_params_dir_set
  4993. ENDIF
  4994. clr Flags3.PGM_DIR_REV
  4995. mov A, @Temp1
  4996. jnb ACC.1, ($+5)
  4997. setb Flags3.PGM_DIR_REV
  4998. decode_params_dir_set:
  4999. clr Flags3.PGM_RCP_PWM_POL
  5000. mov Temp1, #Pgm_Input_Pol
  5001. mov A, @Temp1
  5002. jnb ACC.1, ($+5)
  5003. setb Flags3.PGM_RCP_PWM_POL
  5004. clr C
  5005. mov A, Temp8
  5006. subb A, #2
  5007. jz decode_pwm_freq_low
  5008. mov CKCON, #01h ; Timer0 set for clk/4 (22kHz pwm)
  5009. setb Flags2.PGM_PWM_HIGH_FREQ
  5010. jmp decode_pwm_freq_end
  5011. decode_pwm_freq_low:
  5012. mov CKCON, #00h ; Timer0 set for clk/12 (8kHz pwm)
  5013. clr Flags2.PGM_PWM_HIGH_FREQ
  5014. decode_pwm_freq_end:
  5015. ret
  5016. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5017. ;
  5018. ; Decode governor gain
  5019. ;
  5020. ; No assumptions
  5021. ;
  5022. ; Decodes governor gains
  5023. ;
  5024. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5025. decode_governor_gains:
  5026. ; Decode governor gains
  5027. mov Temp1, #Pgm_Gov_P_Gain ; Decode governor P gain
  5028. mov A, @Temp1
  5029. dec A
  5030. mov DPTR, #GOV_GAIN_TABLE
  5031. movc A, @A+DPTR
  5032. mov Temp1, #Pgm_Gov_P_Gain_Decoded
  5033. mov @Temp1, A
  5034. mov Temp1, #Pgm_Gov_I_Gain ; Decode governor I gain
  5035. mov A, @Temp1
  5036. dec A
  5037. mov DPTR, #GOV_GAIN_TABLE
  5038. movc A, @A+DPTR
  5039. mov Temp1, #Pgm_Gov_I_Gain_Decoded
  5040. mov @Temp1, A
  5041. call switch_power_off ; Reset DPTR
  5042. ret
  5043. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5044. ;
  5045. ; Decode startup power
  5046. ;
  5047. ; No assumptions
  5048. ;
  5049. ; Decodes startup power
  5050. ;
  5051. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5052. decode_startup_power:
  5053. ; Decode startup power
  5054. mov Temp1, #Pgm_Startup_Pwr
  5055. mov A, @Temp1
  5056. dec A
  5057. mov DPTR, #STARTUP_POWER_TABLE
  5058. movc A, @A+DPTR
  5059. mov Temp1, #Pgm_Startup_Pwr_Decoded
  5060. mov @Temp1, A
  5061. call switch_power_off ; Reset DPTR
  5062. ret
  5063. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5064. ;
  5065. ; Decode main spoolup time
  5066. ;
  5067. ; No assumptions
  5068. ;
  5069. ; Decodes main spoolup time
  5070. ;
  5071. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5072. decode_main_spoolup_time:
  5073. IF MODE == 0 ; Main
  5074. ; Decode spoolup time
  5075. mov Temp1, #Pgm_Main_Spoolup_Time
  5076. mov A, @Temp1
  5077. mov Temp1, A ; Store
  5078. jnz ($+3) ; If not zero - branch
  5079. inc Temp1
  5080. clr C
  5081. mov A, Temp1
  5082. subb A, #17 ; Limit to 17 max
  5083. jc ($+4)
  5084. mov Temp1, #17
  5085. mov A, Temp1
  5086. add A, Temp1
  5087. add A, Temp1 ; Now 3x
  5088. mov Main_Spoolup_Time_3x, A
  5089. add A, Main_Spoolup_Time_3x
  5090. add A, Main_Spoolup_Time_3x
  5091. add A, Temp1 ; Now 10x
  5092. mov Main_Spoolup_Time_10x, A
  5093. add A, Main_Spoolup_Time_3x
  5094. add A, Temp1
  5095. add A, Temp1 ; Now 15x
  5096. mov Main_Spoolup_Time_15x, A
  5097. ENDIF
  5098. ret
  5099. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5100. ;
  5101. ; Decode demag compensation
  5102. ;
  5103. ; No assumptions
  5104. ;
  5105. ; Decodes demag comp
  5106. ;
  5107. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5108. decode_demag_comp:
  5109. ; Decode demag compensation
  5110. mov Temp1, #Pgm_Demag_Comp
  5111. mov A, @Temp1
  5112. mov Demag_Pwr_Off_Thresh, #255 ; Set default
  5113. mov Low_Rpm_Pwr_Slope, #12 ; Set default
  5114. cjne A, #2, decode_demag_high
  5115. mov Demag_Pwr_Off_Thresh, #160 ; Settings for demag comp low
  5116. mov Low_Rpm_Pwr_Slope, #10
  5117. decode_demag_high:
  5118. cjne A, #3, decode_demag_done
  5119. mov Demag_Pwr_Off_Thresh, #130 ; Settings for demag comp high
  5120. mov Low_Rpm_Pwr_Slope, #5
  5121. decode_demag_done:
  5122. ret
  5123. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5124. ;
  5125. ; Set BEC voltage
  5126. ;
  5127. ; No assumptions
  5128. ;
  5129. ; Sets the BEC output voltage low or high
  5130. ;
  5131. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5132. set_bec_voltage:
  5133. ; Set bec voltage
  5134. IF HIGH_BEC_VOLTAGE == 1
  5135. Set_BEC_Lo ; Set default to low
  5136. mov Temp1, #Pgm_BEC_Voltage_High
  5137. mov A, @Temp1
  5138. jz set_bec_voltage_exit
  5139. Set_BEC_Hi ; Set to high
  5140. set_bec_voltage_exit:
  5141. ENDIF
  5142. IF HIGH_BEC_VOLTAGE == 2
  5143. Set_BEC_0 ; Set default to low
  5144. mov Temp1, #Pgm_BEC_Voltage_High
  5145. mov A, @Temp1
  5146. cjne A, #1, set_bec_voltage_2
  5147. Set_BEC_1 ; Set to level 1
  5148. set_bec_voltage_2:
  5149. cjne A, #2, set_bec_voltage_exit
  5150. Set_BEC_2 ; Set to level 2
  5151. set_bec_voltage_exit:
  5152. ENDIF
  5153. ret
  5154. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5155. ;
  5156. ; Find throttle gain
  5157. ;
  5158. ; The difference between max and min throttle must be more than 520us (a Pgm_Ppm_xxx_Throttle difference of 130)
  5159. ;
  5160. ; Finds throttle gain from throttle calibration values
  5161. ;
  5162. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5163. find_throttle_gain:
  5164. ; Load programmed minimum and maximum throttle
  5165. mov Temp1, #Pgm_Ppm_Min_Throttle
  5166. mov A, @Temp1
  5167. mov Temp3, A
  5168. mov Temp1, #Pgm_Ppm_Max_Throttle
  5169. mov A, @Temp1
  5170. mov Temp4, A
  5171. ; Check if full range is chosen
  5172. jnb Flags3.FULL_THROTTLE_RANGE, find_throttle_gain_calculate
  5173. mov Temp3, #0
  5174. mov Temp4, #255
  5175. find_throttle_gain_calculate:
  5176. ; Calculate difference
  5177. clr C
  5178. mov A, Temp4
  5179. subb A, Temp3
  5180. mov Temp5, A
  5181. ; Check that difference is minimum 130
  5182. clr C
  5183. subb A, #130
  5184. jnc ($+4)
  5185. mov Temp5, #130
  5186. ; Find gain
  5187. mov Ppm_Throttle_Gain, #0
  5188. test_throttle_gain:
  5189. inc Ppm_Throttle_Gain
  5190. mov A, Temp5
  5191. mov B, Ppm_Throttle_Gain ; A has difference, B has gain
  5192. mul AB
  5193. clr C
  5194. mov A, B
  5195. subb A, #128
  5196. jc test_throttle_gain
  5197. ret
  5198. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5199. ;
  5200. ; Average throttle
  5201. ;
  5202. ; Outputs result in Temp3
  5203. ;
  5204. ; Averages throttle calibration readings
  5205. ;
  5206. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5207. average_throttle:
  5208. setb Flags3.FULL_THROTTLE_RANGE ; Set range to 1000-2020us
  5209. call find_throttle_gain ; Set throttle gain
  5210. call wait30ms
  5211. mov Temp3, #0
  5212. mov Temp4, #0
  5213. mov Temp5, #16 ; Average 16 measurments
  5214. average_throttle_meas:
  5215. call wait3ms ; Wait for new RC pulse value
  5216. mov A, New_Rcp ; Get new RC pulse value
  5217. add A, Temp3
  5218. mov Temp3, A
  5219. mov A, #0
  5220. addc A, Temp4
  5221. mov Temp4, A
  5222. djnz Temp5, average_throttle_meas
  5223. mov Temp5, #4 ; Shift 4 times
  5224. average_throttle_div:
  5225. clr C
  5226. mov A, Temp4 ; Shift right
  5227. rrc A
  5228. mov Temp4, A
  5229. mov A, Temp3
  5230. rrc A
  5231. mov Temp3, A
  5232. djnz Temp5, average_throttle_div
  5233. mov Temp7, A ; Copy to Temp7
  5234. clr Flags3.FULL_THROTTLE_RANGE
  5235. call find_throttle_gain ; Set throttle gain
  5236. ret
  5237. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5238. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5239. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5240. ;
  5241. ; Main program start
  5242. ;
  5243. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5244. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5245. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5246. reset:
  5247. ; Check flash lock byte
  5248. mov A, RSTSRC
  5249. jb ACC.6, ($+6) ; Check if flash access error was reset source
  5250. mov Bit_Access, #0 ; No - then this is the first try
  5251. inc Bit_Access
  5252. mov DPTR, #LOCK_BYTE_ADDRESS_16K ; First try is for 16k flash size
  5253. mov A, Bit_Access
  5254. dec A
  5255. jz lock_byte_test
  5256. mov DPTR, #LOCK_BYTE_ADDRESS_8K ; Second try is for 8k flash size
  5257. dec A
  5258. jz lock_byte_test
  5259. lock_byte_test:
  5260. movc A, @A+DPTR ; Read lock byte
  5261. inc A
  5262. jz lock_byte_ok ; If lock byte is 0xFF, then start code execution
  5263. IF ONE_S_CAPABLE == 0
  5264. mov RSTSRC, #12h ; Generate hardware reset and set VDD monitor
  5265. ELSE
  5266. mov RSTSRC, #10h ; Generate hardware reset and disable VDD monitor
  5267. ENDIF
  5268. lock_byte_ok:
  5269. ; Select register bank 0 for main program routines
  5270. clr PSW.3 ; Select register bank 0 for main program routines
  5271. ; Disable the WDT.
  5272. anl PCA0MD, #NOT(40h) ; Clear watchdog enable bit
  5273. ; Initialize stack
  5274. mov SP, #0c0h ; Stack = 64 upper bytes of RAM
  5275. ; Initialize VDD monitor
  5276. orl VDM0CN, #080h ; Enable the VDD monitor
  5277. call wait1ms ; Wait at least 100us
  5278. IF ONE_S_CAPABLE == 0
  5279. mov RSTSRC, #02h ; Set VDD monitor as a reset source (PORSF) if not 1S capable
  5280. ELSE
  5281. mov RSTSRC, #00h ; Do not set VDD monitor as a reset source for 1S ESCSs, in order to avoid resets due to it
  5282. ENDIF
  5283. ; Set clock frequency
  5284. orl OSCICN, #03h ; Set clock divider to 1
  5285. mov A, OSCICL
  5286. add A, #04h ; 24.5MHz to 25MHz (~0.5% per step)
  5287. jb ACC.7, reset_cal_done ; Is carry (7bit) set? - skip next instruction
  5288. mov OSCICL, A
  5289. reset_cal_done:
  5290. ; Switch power off
  5291. call switch_power_off
  5292. ; Ports initialization
  5293. mov P0, #P0_INIT
  5294. mov P0MDOUT, #P0_PUSHPULL
  5295. mov P0MDIN, #P0_DIGITAL
  5296. mov P0SKIP, #P0_SKIP
  5297. mov P1, #P1_INIT
  5298. mov P1MDOUT, #P1_PUSHPULL
  5299. mov P1MDIN, #P1_DIGITAL
  5300. mov P1SKIP, #P1_SKIP
  5301. IF PORT3_EXIST == 1
  5302. mov P2, #P2_INIT
  5303. ENDIF
  5304. mov P2MDOUT, #P2_PUSHPULL
  5305. IF PORT3_EXIST == 1
  5306. mov P2MDIN, #P2_DIGITAL
  5307. mov P2SKIP, #P2_SKIP
  5308. mov P3, #P3_INIT
  5309. mov P3MDOUT, #P3_PUSHPULL
  5310. mov P3MDIN, #P3_DIGITAL
  5311. ENDIF
  5312. ; Initialize the XBAR and related functionality
  5313. Initialize_Xbar
  5314. ; Set default programmed parameters
  5315. call set_default_parameters
  5316. ; Read all programmed parameters
  5317. call read_all_eeprom_parameters
  5318. ; Set beep strength
  5319. mov Temp1, #Pgm_Beep_Strength
  5320. mov Beep_Strength, @Temp1
  5321. ; Initializing beep
  5322. clr EA ; Disable interrupts explicitly
  5323. call wait200ms
  5324. call beep_f1
  5325. call wait30ms
  5326. call beep_f2
  5327. call wait30ms
  5328. call beep_f3
  5329. call wait30ms
  5330. IF MODE <= 1 ; Main or tail
  5331. ; Wait for receiver to initialize
  5332. call wait1s
  5333. call wait200ms
  5334. call wait200ms
  5335. call wait100ms
  5336. ENDIF
  5337. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5338. ;
  5339. ; No signal entry point
  5340. ;
  5341. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5342. init_no_signal:
  5343. ; Disable interrupts explicitly
  5344. clr EA
  5345. ; Clear RAM
  5346. clr A ; Clear accumulator
  5347. mov Temp1, A ; Clear Temp1
  5348. clear_ram:
  5349. mov @Temp1, A ; Clear RAM
  5350. djnz Temp1, clear_ram ; Is A not zero? - jump
  5351. ; Check if input signal is high for more than 10ms
  5352. mov Temp1, #200
  5353. input_high_check_1:
  5354. mov Temp2, #200
  5355. input_high_check_2:
  5356. jnb RTX_PORT.RTX_PIN, bootloader_done ; Look for low
  5357. djnz Temp2, input_high_check_2
  5358. djnz Temp1, input_high_check_1
  5359. ljmp 1C00h ; Jump to bootloader
  5360. bootloader_done:
  5361. ; Set default programmed parameters
  5362. call set_default_parameters
  5363. ; Read all programmed parameters
  5364. call read_all_eeprom_parameters
  5365. ; Decode parameters
  5366. call decode_parameters
  5367. ; Decode governor gains
  5368. call decode_governor_gains
  5369. ; Decode startup power
  5370. call decode_startup_power
  5371. ; Decode main spoolup time
  5372. call decode_main_spoolup_time
  5373. ; Decode demag compensation
  5374. call decode_demag_comp
  5375. ; Set BEC voltage
  5376. call set_bec_voltage
  5377. ; Find throttle gain from stored min and max settings
  5378. call find_throttle_gain
  5379. ; Set beep strength
  5380. mov Temp1, #Pgm_Beep_Strength
  5381. mov Beep_Strength, @Temp1
  5382. ; Switch power off
  5383. call switch_power_off
  5384. ; Set clock frequency
  5385. IF MCU_50MHZ == 1
  5386. Set_MCU_Clk_25MHz
  5387. ENDIF
  5388. ; Timer control
  5389. mov TCON, #50h ; Timer0 and timer1 enabled
  5390. ; Timer mode
  5391. mov TMOD, #12h ; Timer0 as 8bit, timer1 as 16bit
  5392. ; Timer2: clk/12 for 128us and 32ms interrupts
  5393. mov TMR2CN, #24h ; Timer2 enabled, low counter interrups enabled
  5394. ; Timer3: clk/12 for commutation timing
  5395. mov TMR3CN, #04h ; Timer3 enabled
  5396. ; PCA
  5397. mov PCA0CN, #40h ; PCA enabled
  5398. ; Enable interrupts
  5399. mov IE, #22h ; Enable timer0 and timer2 interrupts
  5400. mov IP, #02h ; High priority to timer0 interrupts
  5401. mov EIE1, #90h ; Enable timer3 and PCA0 interrupts
  5402. ; Initialize comparator
  5403. mov CPT0CN, #80h ; Comparator enabled, no hysteresis
  5404. mov CPT0MD, #00h ; Comparator response time 100ns
  5405. IF COMP1_USED == 1
  5406. mov CPT1CN, #80h ; Comparator enabled, no hysteresis
  5407. mov CPT1MD, #00h ; Comparator response time 100ns
  5408. ENDIF
  5409. ; Initialize ADC
  5410. Initialize_Adc ; Initialize ADC operation
  5411. call wait1ms
  5412. setb EA ; Enable all interrupts
  5413. ; Measure number of lipo cells
  5414. call Measure_Lipo_Cells ; Measure number of lipo cells
  5415. ; Initialize rc pulse
  5416. Rcp_Int_Enable ; Enable interrupt
  5417. Rcp_Clear_Int_Flag ; Clear interrupt flag
  5418. clr Flags2.RCP_EDGE_NO ; Set first edge flag
  5419. call wait200ms
  5420. ; Set initial arm variable
  5421. mov Initial_Arm, #1
  5422. ; Measure PWM frequency
  5423. measure_pwm_freq_init:
  5424. setb Flags0.RCP_MEAS_PWM_FREQ ; Set measure pwm frequency flag
  5425. mov Temp4, #3 ; Number of attempts before going back to detect input signal
  5426. measure_pwm_freq_start:
  5427. mov Temp3, #12 ; Number of pulses to measure
  5428. measure_pwm_freq_loop:
  5429. ; Check if period diff was accepted
  5430. mov A, Rcp_Period_Diff_Accepted
  5431. jnz measure_pwm_freq_wait
  5432. mov Temp3, #12 ; Reset number of pulses to measure
  5433. djnz Temp4, ($+4) ; If it is not zero - proceed
  5434. ajmp init_no_signal ; Go back to detect input signal
  5435. measure_pwm_freq_wait:
  5436. call wait30ms ; Wait 30ms for new pulse
  5437. jb Flags2.RCP_UPDATED, ($+5) ; Is there an updated RC pulse available - proceed
  5438. ajmp init_no_signal ; Go back to detect input signal
  5439. clr Flags2.RCP_UPDATED ; Flag that pulse has been evaluated
  5440. mov A, New_Rcp ; Load value
  5441. clr C
  5442. subb A, #RCP_VALIDATE ; Higher than validate level?
  5443. jc measure_pwm_freq_start ; No - start over
  5444. mov A, Flags3 ; Check pwm frequency flags
  5445. anl A, #((1 SHL RCP_PWM_FREQ_1KHZ)+(1 SHL RCP_PWM_FREQ_2KHZ)+(1 SHL RCP_PWM_FREQ_4KHZ)+(1 SHL RCP_PWM_FREQ_8KHZ)+(1 SHL RCP_PWM_FREQ_12KHZ))
  5446. mov Prev_Rcp_Pwm_Freq, Curr_Rcp_Pwm_Freq ; Store as previous flags for next pulse
  5447. mov Curr_Rcp_Pwm_Freq, A ; Store current flags for next pulse
  5448. cjne A, Prev_Rcp_Pwm_Freq, measure_pwm_freq_start ; Go back if new flags not same as previous
  5449. djnz Temp3, measure_pwm_freq_loop ; Go back if not required number of pulses seen
  5450. ; Clear measure pwm frequency flag
  5451. clr Flags0.RCP_MEAS_PWM_FREQ
  5452. ; Set up RC pulse interrupts after pwm frequency measurement
  5453. Rcp_Int_First ; Enable interrupt and set to first edge
  5454. Rcp_Clear_Int_Flag ; Clear interrupt flag
  5455. clr Flags2.RCP_EDGE_NO ; Set first edge flag
  5456. ; Test whether signal is OnShot125
  5457. clr Flags2.RCP_PPM_ONESHOT125 ; Clear OneShot125 flag
  5458. mov Rcp_Outside_Range_Cnt, #0 ; Reset out of range counter
  5459. call wait100ms ; Wait for new RC pulse
  5460. jnb Flags2.RCP_PPM, validate_rcp_start ; If flag is not set (PWM) - branch
  5461. clr C
  5462. mov A, Rcp_Outside_Range_Cnt ; Check how many pulses were outside normal PPM range (800-2160us)
  5463. subb A, #10
  5464. jc validate_rcp_start
  5465. setb Flags2.RCP_PPM_ONESHOT125 ; Set OneShot125 flag
  5466. ; Validate RC pulse
  5467. validate_rcp_start:
  5468. call wait3ms ; Wait for next pulse (NB: Uses Temp1/2!)
  5469. mov Temp1, #RCP_VALIDATE ; Set validate level as default
  5470. jnb Flags2.RCP_PPM, ($+5) ; If flag is not set (PWM) - branch
  5471. mov Temp1, #0 ; Set level to zero for PPM (any level will be accepted)
  5472. clr C
  5473. mov A, New_Rcp ; Load value
  5474. subb A, Temp1 ; Higher than validate level?
  5475. jc validate_rcp_start ; No - start over
  5476. ; Beep arm sequence start signal
  5477. clr EA ; Disable all interrupts
  5478. call beep_f1 ; Signal that RC pulse is ready
  5479. call beep_f1
  5480. call beep_f1
  5481. setb EA ; Enable all interrupts
  5482. call wait200ms
  5483. ; Arming sequence start
  5484. mov Gov_Arm_Target, #0 ; Clear governor arm target
  5485. arming_start:
  5486. IF MODE >= 1 ; Tail or multi
  5487. mov Temp1, #Pgm_Direction ; Check if bidirectional operation
  5488. mov A, @Temp1
  5489. cjne A, #3, ($+5)
  5490. ajmp program_by_tx_checked ; Disable tx programming if bidirectional operation
  5491. ENDIF
  5492. call wait3ms
  5493. mov Temp1, #Pgm_Enable_TX_Program; Start programming mode entry if enabled
  5494. mov A, @Temp1
  5495. clr C
  5496. subb A, #1 ; Is TX programming enabled?
  5497. jnc arming_initial_arm_check ; Yes - proceed
  5498. jmp program_by_tx_checked ; No - branch
  5499. arming_initial_arm_check:
  5500. mov A, Initial_Arm ; Yes - check if it is initial arm sequence
  5501. clr C
  5502. subb A, #1 ; Is it the initial arm sequence?
  5503. jnc arming_ppm_check ; Yes - proceed
  5504. jmp program_by_tx_checked ; No - branch
  5505. arming_ppm_check:
  5506. jb Flags2.RCP_PPM, throttle_high_cal_start ; If flag is set (PPM) - branch
  5507. ; PWM tx program entry
  5508. clr C
  5509. mov A, New_Rcp ; Load new RC pulse value
  5510. subb A, #RCP_MAX ; Is RC pulse max?
  5511. jnc program_by_tx_entry_pwm ; Yes - proceed
  5512. jmp program_by_tx_checked ; No - branch
  5513. program_by_tx_entry_pwm:
  5514. clr EA ; Disable all interrupts
  5515. call beep_f4
  5516. setb EA ; Enable all interrupts
  5517. call wait100ms
  5518. clr C
  5519. mov A, New_Rcp ; Load new RC pulse value
  5520. subb A, #RCP_STOP ; Below stop?
  5521. jnc program_by_tx_entry_pwm ; No - start over
  5522. program_by_tx_entry_wait_pwm:
  5523. clr EA ; Disable all interrupts
  5524. call beep_f1
  5525. call wait10ms
  5526. call beep_f1
  5527. setb EA ; Enable all interrupts
  5528. call wait100ms
  5529. clr C
  5530. mov A, New_Rcp ; Load new RC pulse value
  5531. subb A, #RCP_MAX ; At or above max?
  5532. jc program_by_tx_entry_wait_pwm ; No - start over
  5533. jmp program_by_tx ; Yes - enter programming mode
  5534. ; PPM throttle calibration and tx program entry
  5535. throttle_high_cal_start:
  5536. IF MODE <= 1 ; Main or tail
  5537. mov Temp8, #5 ; Set 3 seconds wait time
  5538. ELSE
  5539. mov Temp8, #2 ; Set 1 seconds wait time
  5540. ENDIF
  5541. throttle_high_cal:
  5542. setb Flags3.FULL_THROTTLE_RANGE ; Set range to 1000-2020us
  5543. call find_throttle_gain ; Set throttle gain
  5544. call wait100ms ; Wait for new throttle value
  5545. clr EA ; Disable interrupts (freeze New_Rcp value)
  5546. clr Flags3.FULL_THROTTLE_RANGE ; Set programmed range
  5547. call find_throttle_gain ; Set throttle gain
  5548. mov Temp7, New_Rcp ; Store new RC pulse value
  5549. clr C
  5550. mov A, New_Rcp ; Load new RC pulse value
  5551. subb A, #(RCP_MAX/2) ; Is RC pulse above midstick?
  5552. setb EA ; Enable interrupts
  5553. jc arm_target_updated ; No - branch
  5554. call wait1ms
  5555. clr EA ; Disable all interrupts
  5556. call beep_f4
  5557. setb EA ; Enable all interrupts
  5558. djnz Temp8, throttle_high_cal ; Continue to wait
  5559. call average_throttle
  5560. clr C
  5561. mov A, Temp7 ; Limit to max 250
  5562. subb A, #5 ; Subtract about 2% and ensure that it is 250 or lower
  5563. mov Temp1, #Pgm_Ppm_Max_Throttle ; Store
  5564. mov @Temp1, A
  5565. call wait200ms
  5566. call erase_and_store_all_in_eeprom
  5567. call success_beep
  5568. throttle_low_cal_start:
  5569. mov Temp8, #10 ; Set 3 seconds wait time
  5570. throttle_low_cal:
  5571. setb Flags3.FULL_THROTTLE_RANGE ; Set range to 1000-2020us
  5572. call find_throttle_gain ; Set throttle gain
  5573. call wait100ms
  5574. clr EA ; Disable interrupts (freeze New_Rcp value)
  5575. clr Flags3.FULL_THROTTLE_RANGE ; Set programmed range
  5576. call find_throttle_gain ; Set throttle gain
  5577. mov Temp7, New_Rcp ; Store new RC pulse value
  5578. clr C
  5579. mov A, New_Rcp ; Load new RC pulse value
  5580. subb A, #(RCP_MAX/2) ; Below midstick?
  5581. setb EA ; Enable interrupts
  5582. jnc throttle_low_cal_start ; No - start over
  5583. call wait1ms
  5584. clr EA ; Disable all interrupts
  5585. call beep_f1
  5586. call wait10ms
  5587. call beep_f1
  5588. setb EA ; Enable all interrupts
  5589. djnz Temp8, throttle_low_cal ; Continue to wait
  5590. call average_throttle
  5591. mov A, Temp7
  5592. add A, #5 ; Add about 2%
  5593. mov Temp1, #Pgm_Ppm_Min_Throttle ; Store
  5594. mov @Temp1, A
  5595. call wait200ms
  5596. call erase_and_store_all_in_eeprom
  5597. call success_beep_inverted
  5598. program_by_tx_entry_wait_ppm:
  5599. call wait100ms
  5600. call find_throttle_gain ; Set throttle gain
  5601. clr C
  5602. mov A, New_Rcp ; Load new RC pulse value
  5603. subb A, #RCP_MAX ; At or above max?
  5604. jc program_by_tx_entry_wait_ppm ; No - start over
  5605. jmp program_by_tx ; Yes - enter programming mode
  5606. program_by_tx_checked:
  5607. clr C
  5608. mov A, New_Rcp ; Load new RC pulse value
  5609. subb A, Gov_Arm_Target ; Is RC pulse larger than arm target?
  5610. jc arm_target_updated ; No - do not update
  5611. mov Gov_Arm_Target, New_Rcp ; Yes - update arm target
  5612. arm_target_updated:
  5613. call wait100ms ; Wait for new throttle value
  5614. mov Temp1, #RCP_STOP ; Default stop value
  5615. mov Temp2, #Pgm_Direction ; Check if bidirectional operation
  5616. mov A, @Temp2
  5617. cjne A, #3, ($+5) ; No - branch
  5618. mov Temp1, #(RCP_STOP+4) ; Higher stop value for bidirectional
  5619. clr C
  5620. mov A, New_Rcp ; Load new RC pulse value
  5621. subb A, Temp1 ; Below stop?
  5622. jc arm_end_beep ; Yes - proceed
  5623. jmp arming_start ; No - start over
  5624. arm_end_beep:
  5625. ; Beep arm sequence end signal
  5626. clr EA ; Disable all interrupts
  5627. call beep_f4 ; Signal that rcpulse is ready
  5628. call beep_f4
  5629. call beep_f4
  5630. setb EA ; Enable all interrupts
  5631. call wait200ms
  5632. ; Clear initial arm variable
  5633. mov Initial_Arm, #0
  5634. ; Armed and waiting for power on
  5635. wait_for_power_on:
  5636. clr A
  5637. mov Power_On_Wait_Cnt_L, A ; Clear wait counter
  5638. mov Power_On_Wait_Cnt_H, A
  5639. wait_for_power_on_loop:
  5640. inc Power_On_Wait_Cnt_L ; Increment low wait counter
  5641. mov A, Power_On_Wait_Cnt_L
  5642. cpl A
  5643. jnz wait_for_power_on_no_beep; Counter wrapping (about 1 sec)?
  5644. inc Power_On_Wait_Cnt_H ; Increment high wait counter
  5645. mov Temp1, #Pgm_Beacon_Delay
  5646. mov A, @Temp1
  5647. mov Temp1, #25 ; Approximately 1 min
  5648. dec A
  5649. jz beep_delay_set
  5650. mov Temp1, #50 ; Approximately 2 min
  5651. dec A
  5652. jz beep_delay_set
  5653. mov Temp1, #125 ; Approximately 5 min
  5654. dec A
  5655. jz beep_delay_set
  5656. mov Temp1, #250 ; Approximately 10 min
  5657. dec A
  5658. jz beep_delay_set
  5659. mov Power_On_Wait_Cnt_H, #0 ; Reset counter for infinite delay
  5660. beep_delay_set:
  5661. clr C
  5662. mov A, Power_On_Wait_Cnt_H
  5663. subb A, Temp1 ; Check against chosen delay
  5664. jc wait_for_power_on_no_beep; Has delay elapsed?
  5665. dec Power_On_Wait_Cnt_H ; Decrement high wait counter
  5666. mov Power_On_Wait_Cnt_L, #180; Set low wait counter
  5667. mov Temp1, #Pgm_Beacon_Strength
  5668. mov Beep_Strength, @Temp1
  5669. clr EA ; Disable all interrupts
  5670. call beep_f4 ; Signal that there is no signal
  5671. setb EA ; Enable all interrupts
  5672. mov Temp1, #Pgm_Beep_Strength
  5673. mov Beep_Strength, @Temp1
  5674. call wait100ms ; Wait for new RC pulse to be measured
  5675. wait_for_power_on_no_beep:
  5676. call wait10ms
  5677. mov A, Rcp_Timeout_Cnt ; Load RC pulse timeout counter value
  5678. jnz wait_for_power_on_ppm_not_missing ; If it is not zero - proceed
  5679. jnb Flags2.RCP_PPM, wait_for_power_on_ppm_not_missing ; If flag is not set (PWM) - branch
  5680. jmp init_no_signal ; If ppm and pulses missing - go back to detect input signal
  5681. wait_for_power_on_ppm_not_missing:
  5682. mov Temp1, #RCP_STOP
  5683. jb Flags2.RCP_PPM, ($+5) ; If flag is set (PPM) - branch
  5684. mov Temp1, #(RCP_STOP+5) ; Higher than stop (for pwm)
  5685. clr C
  5686. mov A, New_Rcp ; Load new RC pulse value
  5687. subb A, Temp1 ; Higher than stop (plus some hysteresis)?
  5688. jc wait_for_power_on_loop ; No - start over
  5689. IF MODE >= 1 ; Tail or multi
  5690. mov Temp1, #Pgm_Direction ; Check if bidirectional operation
  5691. mov A, @Temp1
  5692. clr C
  5693. subb A, #3
  5694. jz wait_for_power_on_check_timeout ; Do not wait if bidirectional operation
  5695. ENDIF
  5696. lcall wait100ms ; Wait to see if start pulse was only a glitch
  5697. wait_for_power_on_check_timeout:
  5698. mov A, Rcp_Timeout_Cnt ; Load RC pulse timeout counter value
  5699. jnz ($+4) ; If it is not zero - proceed
  5700. ajmp init_no_signal ; If it is zero (pulses missing) - go back to detect input signal
  5701. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5702. ;
  5703. ; Start entry point
  5704. ;
  5705. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5706. init_start:
  5707. clr EA
  5708. call switch_power_off
  5709. clr A
  5710. mov Requested_Pwm, A ; Set requested pwm to zero
  5711. mov Governor_Req_Pwm, A ; Set governor requested pwm to zero
  5712. mov Current_Pwm, A ; Set current pwm to zero
  5713. mov Current_Pwm_Limited, A ; Set limited current pwm to zero
  5714. setb EA
  5715. mov Temp1, #Pgm_Motor_Idle
  5716. mov Pwm_Motor_Idle, @Temp1 ; Set idle pwm to programmed value
  5717. mov Gov_Target_L, A ; Set target to zero
  5718. mov Gov_Target_H, A
  5719. mov Gov_Integral_L, A ; Set integral to zero
  5720. mov Gov_Integral_H, A
  5721. mov Gov_Integral_X, A
  5722. mov Adc_Conversion_Cnt, A
  5723. mov Gov_Active, A
  5724. mov Flags0, A ; Clear flags0
  5725. mov Flags1, A ; Clear flags1
  5726. mov Demag_Detected_Metric, A ; Clear demag metric
  5727. call initialize_all_timings ; Initialize timing
  5728. ;**** **** **** **** ****
  5729. ; Motor start beginning
  5730. ;**** **** **** **** ****
  5731. mov Adc_Conversion_Cnt, #TEMP_CHECK_RATE ; Make sure a temp reading is done
  5732. Set_Adc_Ip_Temp
  5733. call wait1ms
  5734. call start_adc_conversion
  5735. read_initial_temp:
  5736. Get_Adc_Status
  5737. jb AD0BUSY, read_initial_temp
  5738. Read_Adc_Result ; Read initial temperature
  5739. mov A, Temp2
  5740. jnz ($+3) ; Is reading below 256?
  5741. mov Temp1, A ; Yes - set average temperature value to zero
  5742. mov Current_Average_Temp, Temp1 ; Set initial average temperature
  5743. call check_temp_voltage_and_limit_power
  5744. mov Adc_Conversion_Cnt, #TEMP_CHECK_RATE ; Make sure a temp reading is done next time
  5745. Set_Adc_Ip_Temp
  5746. ; Set up start operating conditions
  5747. mov Temp1, #Pgm_Pwm_Freq
  5748. mov A, @Temp1
  5749. mov Temp7, A ; Store setting in Temp7
  5750. mov @Temp1, #2 ; Set nondamped low frequency pwm mode
  5751. call decode_parameters ; (Decode_parameters uses Temp1 and Temp8)
  5752. mov Temp1, #Pgm_Pwm_Freq
  5753. mov A, Temp7
  5754. mov @Temp1, A ; Restore settings
  5755. ; Set max allowed power
  5756. clr EA ; Disable interrupts to avoid that Requested_Pwm is overwritten
  5757. mov Pwm_Limit, #0FFh ; Set pwm limit to max
  5758. call set_startup_pwm
  5759. mov Pwm_Limit, Requested_Pwm
  5760. mov Pwm_Limit_Spoolup, Requested_Pwm
  5761. mov Pwm_Limit_Low_Rpm, Requested_Pwm
  5762. setb EA
  5763. mov Requested_Pwm, #1 ; Set low pwm again after calling set_startup_pwm
  5764. mov Current_Pwm, #1
  5765. mov Current_Pwm_Limited, #1
  5766. mov Spoolup_Limit_Cnt, Auto_Bailout_Armed
  5767. mov Spoolup_Limit_Skip, #1
  5768. ; Begin startup sequence
  5769. IF MCU_50MHZ == 1
  5770. Set_MCU_Clk_50MHz
  5771. ENDIF
  5772. setb Flags1.MOTOR_SPINNING ; Set motor spinning flag
  5773. setb Flags1.STARTUP_PHASE ; Set startup phase flag
  5774. mov Startup_Ok_Cnt, #0 ; Reset ok counter
  5775. call comm5comm6 ; Initialize commutation
  5776. call comm6comm1
  5777. call initialize_all_timings ; Initialize timing
  5778. call calc_next_comm_timing ; Set virtual commutation point
  5779. call calc_new_wait_times ; Calculate new wait times
  5780. jmp run1
  5781. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5782. ;
  5783. ; Run entry point
  5784. ;
  5785. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5786. damped_transition:
  5787. ; Transition from nondamped to damped if applicable
  5788. call switch_power_off ; Switch off power while changing pwm mode
  5789. call decode_parameters ; Set programmed parameters
  5790. mov Adc_Conversion_Cnt, #0 ; Make sure a voltage reading is done next time
  5791. Set_Adc_Ip_Volt ; Set adc measurement to voltage
  5792. ; Run 1 = B(p-on) + C(n-pwm) - comparator A evaluated
  5793. ; Out_cA changes from low to high
  5794. run1:
  5795. call wait_for_comp_out_high ; Wait zero cross wait and wait for high
  5796. call evaluate_comparator_integrity ; Check whether comparator reading has been normal
  5797. call setup_comm_wait ; Setup wait time from zero cross to commutation
  5798. call calc_governor_target ; Calculate governor target
  5799. call wait_for_comm ; Wait from zero cross to commutation
  5800. call comm1comm2 ; Commutate
  5801. call calc_next_comm_timing ; Calculate next timing and start advance timing wait
  5802. call wait_advance_timing ; Wait advance timing and start zero cross wait
  5803. call calc_new_wait_times
  5804. call wait_before_zc_scan ; Wait zero cross wait and start zero cross timeout
  5805. ; Run 2 = A(p-on) + C(n-pwm) - comparator B evaluated
  5806. ; Out_cB changes from high to low
  5807. run2:
  5808. call wait_for_comp_out_low
  5809. call evaluate_comparator_integrity
  5810. call setup_comm_wait
  5811. call calc_governor_prop_error
  5812. call set_pwm_limit_low_rpm
  5813. call wait_for_comm
  5814. call comm2comm3
  5815. call calc_next_comm_timing
  5816. call wait_advance_timing
  5817. call calc_new_wait_times
  5818. call wait_before_zc_scan
  5819. ; Run 3 = A(p-on) + B(n-pwm) - comparator C evaluated
  5820. ; Out_cC changes from low to high
  5821. run3:
  5822. call wait_for_comp_out_high
  5823. call evaluate_comparator_integrity
  5824. call setup_comm_wait
  5825. call calc_governor_int_error
  5826. call wait_for_comm
  5827. call comm3comm4
  5828. call calc_next_comm_timing
  5829. call wait_advance_timing
  5830. call calc_new_wait_times
  5831. call wait_before_zc_scan
  5832. ; Run 4 = C(p-on) + B(n-pwm) - comparator A evaluated
  5833. ; Out_cA changes from high to low
  5834. run4:
  5835. call wait_for_comp_out_low
  5836. call evaluate_comparator_integrity
  5837. call setup_comm_wait
  5838. call calc_governor_prop_correction
  5839. call wait_for_comm
  5840. call comm4comm5
  5841. call calc_next_comm_timing
  5842. call wait_advance_timing
  5843. call calc_new_wait_times
  5844. call wait_before_zc_scan
  5845. ; Run 5 = C(p-on) + A(n-pwm) - comparator B evaluated
  5846. ; Out_cB changes from low to high
  5847. run5:
  5848. call wait_for_comp_out_high
  5849. call evaluate_comparator_integrity
  5850. call setup_comm_wait
  5851. call calc_governor_int_correction
  5852. call wait_for_comm
  5853. call comm5comm6
  5854. call calc_next_comm_timing
  5855. call wait_advance_timing
  5856. call calc_new_wait_times
  5857. call wait_before_zc_scan
  5858. ; Run 6 = B(p-on) + A(n-pwm) - comparator C evaluated
  5859. ; Out_cC changes from high to low
  5860. run6:
  5861. call wait_for_comp_out_low
  5862. call start_adc_conversion
  5863. call evaluate_comparator_integrity
  5864. call setup_comm_wait
  5865. call check_temp_voltage_and_limit_power
  5866. call wait_for_comm
  5867. call comm6comm1
  5868. call calc_next_comm_timing
  5869. call wait_advance_timing
  5870. call calc_new_wait_times
  5871. call wait_before_zc_scan
  5872. ; Check if it is direct startup
  5873. jnb Flags1.STARTUP_PHASE, normal_run_checks
  5874. jb Flags1.DIR_CHANGE_BRAKE, normal_run_checks ; If a direction change - branch
  5875. ; Set spoolup power variables
  5876. mov Pwm_Limit, Pwm_Spoolup_Beg ; Set initial max power
  5877. mov Pwm_Limit_Spoolup, Pwm_Spoolup_Beg ; Set initial slow spoolup power
  5878. mov Spoolup_Limit_Cnt, Auto_Bailout_Armed
  5879. mov Spoolup_Limit_Skip, #1
  5880. ; Check startup ok counter
  5881. mov Temp2, #50 ; Set nominal startup parameters
  5882. mov Temp3, #10
  5883. clr C
  5884. mov A, Startup_Ok_Cnt ; Load ok counter
  5885. subb A, Temp2 ; Is counter above requirement?
  5886. jc direct_start_check_rcp ; No - proceed
  5887. clr Flags1.STARTUP_PHASE ; Clear startup phase flag
  5888. setb Flags1.INITIAL_RUN_PHASE ; Set initial run phase flag
  5889. mov Startup_Rot_Cnt, Temp3 ; Set startup rotation count
  5890. IF MODE == 1 ; Tail
  5891. mov Pwm_Limit, #0FFh ; Allow full power
  5892. mov Pwm_Limit_Spoolup, #0FFh
  5893. ENDIF
  5894. IF MODE == 2 ; Multi
  5895. mov Pwm_Limit, Pwm_Spoolup_Beg
  5896. mov Pwm_Limit_Spoolup, #0FFh
  5897. mov Pwm_Limit_Low_Rpm, #20h
  5898. ENDIF
  5899. jmp normal_run_checks
  5900. direct_start_check_rcp:
  5901. clr C
  5902. mov A, New_Rcp ; Load new pulse value
  5903. subb A, #RCP_STOP ; Check if pulse is below stop value
  5904. jc ($+5)
  5905. ljmp run1 ; Continue to run
  5906. jmp run_to_wait_for_power_on
  5907. normal_run_checks:
  5908. ; Check if it is initial run phase
  5909. jnb Flags1.INITIAL_RUN_PHASE, initial_run_phase_done ; If not initial run phase - branch
  5910. jb Flags1.DIR_CHANGE_BRAKE, initial_run_phase_done ; If a direction change - branch
  5911. ; Decrement startup rotaton count
  5912. mov A, Startup_Rot_Cnt
  5913. dec A
  5914. ; Check number of nondamped rotations
  5915. jnz normal_run_check_startup_rot ; Branch if counter is not zero
  5916. clr Flags1.INITIAL_RUN_PHASE ; Clear initial run phase flag
  5917. IF MODE == 2 ; Multi
  5918. mov Pwm_Limit, #0FFh
  5919. ENDIF
  5920. jmp damped_transition ; Do damped transition if counter is zero
  5921. normal_run_check_startup_rot:
  5922. mov Startup_Rot_Cnt, A ; Not zero - store counter
  5923. clr C
  5924. mov A, New_Rcp ; Load new pulse value
  5925. subb A, #RCP_STOP ; Check if pulse is below stop value
  5926. jc ($+5)
  5927. ljmp run1 ; Continue to run
  5928. jmp run_to_wait_for_power_on
  5929. initial_run_phase_done:
  5930. IF MODE == 0 ; Main
  5931. ; Check if throttle is zeroed
  5932. clr C
  5933. mov A, Rcp_Stop_Cnt ; Load stop RC pulse counter value
  5934. subb A, #1 ; Is number of stop RC pulses above limit?
  5935. jc run6_check_rcp_stop_count ; If no - branch
  5936. mov Pwm_Limit_Spoolup, Pwm_Spoolup_Beg ; If yes - set initial max powers
  5937. mov Spoolup_Limit_Cnt, Auto_Bailout_Armed ; And set spoolup parameters
  5938. mov Spoolup_Limit_Skip, #1
  5939. run6_check_rcp_stop_count:
  5940. ENDIF
  5941. ; Exit run loop after a given time
  5942. clr C
  5943. mov A, Rcp_Stop_Cnt ; Load stop RC pulse counter low byte value
  5944. subb A, #RCP_STOP_LIMIT ; Is number of stop RC pulses above limit?
  5945. jnc run_to_wait_for_power_on ; Yes, go back to wait for poweron
  5946. run6_check_rcp_timeout:
  5947. jnb Flags2.RCP_PPM, run6_check_speed ; If flag is not set (PWM) - branch
  5948. mov A, Rcp_Timeout_Cnt ; Load RC pulse timeout counter value
  5949. jz run_to_wait_for_power_on ; If it is zero - go back to wait for poweron
  5950. run6_check_speed:
  5951. clr C
  5952. mov A, Comm_Period4x_H ; Is Comm_Period4x more than 32ms (~1220 eRPM)?
  5953. mov Temp1, #0F0h ; Default minimum speed
  5954. jnb Flags1.DIR_CHANGE_BRAKE, ($+5); Is it a direction change?
  5955. mov Temp1, #60h ; Bidirectional minimum speed
  5956. subb A, Temp1
  5957. jnc run_to_wait_for_power_on ; Yes - go back to motor start
  5958. jmp run1 ; Go back to run 1
  5959. run_to_wait_for_power_on:
  5960. clr EA
  5961. call switch_power_off
  5962. mov Temp1, #Pgm_Pwm_Freq
  5963. mov A, @Temp1
  5964. mov Temp7, A ; Store setting in Temp7
  5965. mov @Temp1, #2 ; Set low pwm mode (in order to turn off damping)
  5966. call decode_parameters ; (Decode_parameters uses Temp1 and Temp8)
  5967. mov Temp1, #Pgm_Pwm_Freq
  5968. mov A, Temp7
  5969. mov @Temp1, A ; Restore settings
  5970. clr A
  5971. mov Requested_Pwm, A ; Set requested pwm to zero
  5972. mov Governor_Req_Pwm, A ; Set governor requested pwm to zero
  5973. mov Current_Pwm, A ; Set current pwm to zero
  5974. mov Current_Pwm_Limited, A ; Set limited current pwm to zero
  5975. mov Pwm_Motor_Idle, A ; Set motor idle to zero
  5976. clr Flags1.MOTOR_SPINNING ; Clear motor spinning flag
  5977. IF MCU_50MHZ == 1
  5978. Set_MCU_Clk_25MHz
  5979. ENDIF
  5980. setb EA
  5981. call wait1ms ; Wait for pwm to be stopped
  5982. call switch_power_off
  5983. IF MODE == 0 ; Main
  5984. jnb Flags2.RCP_PPM, run_to_next_state_main ; If flag is not set (PWM) - branch
  5985. mov A, Rcp_Timeout_Cnt ; Load RC pulse timeout counter value
  5986. jnz run_to_next_state_main ; If it is not zero - branch
  5987. jmp init_no_signal ; If it is zero (pulses missing) - go back to detect input signal
  5988. run_to_next_state_main:
  5989. mov Temp1, #Pgm_Main_Rearm_Start
  5990. mov A, @Temp1
  5991. clr C
  5992. subb A, #1 ; Is re-armed start enabled?
  5993. jc jmp_wait_for_power_on ; No - do like tail and start immediately
  5994. jmp validate_rcp_start ; Yes - go back to validate RC pulse
  5995. jmp_wait_for_power_on:
  5996. jmp wait_for_power_on ; Go back to wait for power on
  5997. ENDIF
  5998. IF MODE >= 1 ; Tail or multi
  5999. jnb Flags2.RCP_PPM, jmp_wait_for_power_on ; If flag is not set (PWM) - branch
  6000. mov A, Rcp_Timeout_Cnt ; Load RC pulse timeout counter value
  6001. jnz jmp_wait_for_power_on ; If it is not zero - go back to wait for poweron
  6002. jmp init_no_signal ; If it is zero (pulses missing) - go back to detect input signal
  6003. jmp_wait_for_power_on:
  6004. jmp wait_for_power_on ; Go back to wait for power on
  6005. ENDIF
  6006. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  6007. $include (BLHeliTxPgm.inc) ; Include source code for programming the ESC with the TX
  6008. $include (BLHeliBootLoad.inc) ; Include source code for bootloader
  6009. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  6010. ; TEST code size
  6011. ;CSEG AT 1E00h ; Last code segment. Take care that there is enough space!
  6012. ;nop
  6013. END