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.

8236 lines
250 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
9 years ago
9 years ago
12 years ago
9 years ago
9 years ago
9 years ago
9 years ago
9 years ago
9 years ago
9 years ago
9 years ago
9 years ago
9 years ago
9 years ago
9 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
9 years ago
9 years ago
9 years ago
9 years ago
9 years ago
9 years ago
9 years ago
9 years ago
9 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
9 years ago
12 years ago
9 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
9 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
12 years ago
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 autodetects the various input modes/frequencies
  36. ; The code 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 48MHz capable SiLabs MCUs at 48MHz
  206. ; Added bootlader to SiLabs code
  207. ; Miscellaneous other changes
  208. ; - Rev14.0 Improved running at high timing
  209. ; Improved running at high RPMs and increased max RPM limit
  210. ; Avoid being locked in bootloader (implemented in Suite 13202)
  211. ; Improved reliability of 3D (bidirectional) mode and startup
  212. ; Smoother running and greatly reduced step to full power in damped light mode
  213. ; Removed low voltage limiting for MULTI
  214. ; Added pwm dither parameter
  215. ; Added setting for enable/disable of low RPM power protection
  216. ; Added setting for enable/disable of PWM input
  217. ; Better AFW and damping for some ESCs (that have a slow high side driver)
  218. ; Miscellaneous other changes
  219. ; - Rev14.1 Fixed max throttle calibration bug (for non-oneshot)
  220. ; Fixed some closed loop mode bugs
  221. ; Relaxed signal jitter requirement for looptimes below 1000
  222. ; Added skipping of damping fet switching near max power, for improved high end throttle linearity, using the concept of SimonK
  223. ; Improved sync hold at high rpms
  224. ; - Rev14.2 Added stalled motor shutoff after about 10 seconds (for tail and multi code with PPM input)
  225. ; Greatly increased maximum rpm limit, and added rpm limiting at 250k erpm (48MHz MCUs at 400k erpm)
  226. ; Improved bidirectional operation
  227. ; - Rev14.3 Moved reset vector to be just before the settings segment, in order to better recover from partially failed flashing operation
  228. ; Added 100ms intialization delay for the Graupner Ultra 20A ESC
  229. ; Shortened stall detect time to about 5sec, and prevented going into tx programming after a stall
  230. ; Optimizations of software timing and running reliability
  231. ; - Rev14.4 Improved startup, particularly for larger motors
  232. ; Improved running at very high rpms
  233. ; Made damped light default for MULTI on ESCs that support it
  234. ; Miscellaneous other changes
  235. ; - Rev14.5 Longer between beacon beeps (to reduce motor heating), and now again beeping on two motor phases
  236. ; Implemented programmable brake on zero throttle
  237. ; Implemented hardware reload of commutation timers, to reduce sensitivity to interrupt activity on high rpms
  238. ; Implemented support for EN/PWM style fet drivers
  239. ; Slightly modified throttle calibration
  240. ; Improved startup, particularly for small motors
  241. ; Improved smoothness
  242. ; - Rev14.6 Fixed bug that caused tail motor not to stop
  243. ; Fixed bug that caused brake not to work for low side pwm ESCs
  244. ; Fixed bug where noisy input signal could cause loss of sync
  245. ; Increased fet deadtime a bit for the LB20A and the LB20A pro
  246. ; Made low rpm power limiting programmable through the startup power parameter
  247. ; - Rev14.7 Beeps can be turned off by programming beep strength to 1
  248. ; Throttle cal difference is checked to be above required minimum before storing. Throttle cal max is not stored until successful min throttle cal
  249. ; In order to have a good code for fixed wing planes, that has low voltage limiting, a main code spoolup time setting of 0 is made fast
  250. ; Improved protection of bootloader and generally reduced risk of flash corruption
  251. ; Some small changes for improved sync hold
  252. ; - Rev14.8 Fixed bug where bootloader operation could be blocked by a defective "eeprom" signature
  253. ; - Rev14.9 Improved bidirectional mode for high input signal rates
  254. ;
  255. ;
  256. ;**** **** **** **** ****
  257. ; Up to 8K Bytes of In-System Self-Programmable Flash
  258. ; Up to 768 Bytes Internal SRAM
  259. ;
  260. ;**** **** **** **** ****
  261. ; Master clock is internal 24MHz oscillator (or 48MHz, for which the times below are halved)
  262. ; Timer 0 (167/500ns counts) always counts up and is used for
  263. ; - PWM generation
  264. ; Timer 2 (500ns counts) always counts up and is used for
  265. ; - RC pulse timeout/skip counts and commutation times
  266. ; Timer 3 (500ns counts) always counts up and is used for
  267. ; - Commutation timeouts
  268. ; PCA0 (500ns counts) always counts up and is used for
  269. ; - RC pulse measurement
  270. ;
  271. ;**** **** **** **** ****
  272. ; Interrupt handling
  273. ; The C8051 does not disable interrupts when entering an interrupt routine.
  274. ; Also some interrupt flags need to be cleared by software
  275. ; The code disables interrupts in interrupt routines, in order to avoid too nested interrupts
  276. ; - Interrupts are disabled during beeps, to avoid audible interference from interrupts
  277. ; - RC pulse interrupts are periodically disabled in order to reduce interference with pwm interrupts.
  278. ;
  279. ;**** **** **** **** ****
  280. ; Motor control:
  281. ; - Brushless motor control with 6 states for each electrical 360 degrees
  282. ; - An advance timing of 0deg has zero cross 30deg after one commutation and 30deg before the next
  283. ; - Timing advance in this implementation is set to 15deg nominally
  284. ; - "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.
  285. ; Motor sequence starting from zero crossing:
  286. ; - Timer wait: Wt_Comm 15deg ; Time to wait from zero cross to actual commutation
  287. ; - Timer wait: Wt_Advance 15deg ; Time to wait for timing advance. Nominal commutation point is after this
  288. ; - Timer wait: Wt_Zc_Scan 7.5deg ; Time to wait before looking for zero cross
  289. ; - Scan for zero cross 22.5deg , Nominal, with some motor variations
  290. ;
  291. ; Motor startup:
  292. ; There is a startup phase and an initial run phase, before normal bemf commutation run begins.
  293. ;
  294. ;**** **** **** **** ****
  295. ; List of enumerated supported ESCs and modes (main, tail or multi)
  296. XP_3A_Main EQU 1
  297. XP_3A_Tail EQU 2
  298. XP_3A_Multi EQU 3
  299. XP_7A_Main EQU 4
  300. XP_7A_Tail EQU 5
  301. XP_7A_Multi EQU 6
  302. XP_7A_Fast_Main EQU 7
  303. XP_7A_Fast_Tail EQU 8
  304. XP_7A_Fast_Multi EQU 9
  305. XP_12A_Main EQU 10
  306. XP_12A_Tail EQU 11
  307. XP_12A_Multi EQU 12
  308. XP_18A_Main EQU 13
  309. XP_18A_Tail EQU 14
  310. XP_18A_Multi EQU 15
  311. XP_25A_Main EQU 16
  312. XP_25A_Tail EQU 17
  313. XP_25A_Multi EQU 18
  314. XP_35A_SW_Main EQU 19
  315. XP_35A_SW_Tail EQU 20
  316. XP_35A_SW_Multi EQU 21
  317. DP_3A_Main EQU 22
  318. DP_3A_Tail EQU 23
  319. DP_3A_Multi EQU 24
  320. Supermicro_3p5A_Main EQU 25
  321. Supermicro_3p5A_Tail EQU 26
  322. Supermicro_3p5A_Multi EQU 27
  323. Turnigy_Plush_6A_Main EQU 28
  324. Turnigy_Plush_6A_Tail EQU 29
  325. Turnigy_Plush_6A_Multi EQU 30
  326. Turnigy_Plush_10A_Main EQU 31
  327. Turnigy_Plush_10A_Tail EQU 32
  328. Turnigy_Plush_10A_Multi EQU 33
  329. Turnigy_Plush_12A_Main EQU 34
  330. Turnigy_Plush_12A_Tail EQU 35
  331. Turnigy_Plush_12A_Multi EQU 36
  332. Turnigy_Plush_18A_Main EQU 37
  333. Turnigy_Plush_18A_Tail EQU 38
  334. Turnigy_Plush_18A_Multi EQU 39
  335. Turnigy_Plush_25A_Main EQU 40
  336. Turnigy_Plush_25A_Tail EQU 41
  337. Turnigy_Plush_25A_Multi EQU 42
  338. Turnigy_Plush_30A_Main EQU 43
  339. Turnigy_Plush_30A_Tail EQU 44
  340. Turnigy_Plush_30A_Multi EQU 45
  341. Turnigy_Plush_40A_Main EQU 46
  342. Turnigy_Plush_40A_Tail EQU 47
  343. Turnigy_Plush_40A_Multi EQU 48
  344. Turnigy_Plush_60A_Main EQU 49
  345. Turnigy_Plush_60A_Tail EQU 50
  346. Turnigy_Plush_60A_Multi EQU 51
  347. Turnigy_Plush_80A_Main EQU 52
  348. Turnigy_Plush_80A_Tail EQU 53
  349. Turnigy_Plush_80A_Multi EQU 54
  350. Turnigy_Plush_Nfet_18A_Main EQU 55
  351. Turnigy_Plush_Nfet_18A_Tail EQU 56
  352. Turnigy_Plush_Nfet_18A_Multi EQU 57
  353. Turnigy_Plush_Nfet_25A_Main EQU 58
  354. Turnigy_Plush_Nfet_25A_Tail EQU 59
  355. Turnigy_Plush_Nfet_25A_Multi EQU 60
  356. Turnigy_Plush_Nfet_30A_Main EQU 61
  357. Turnigy_Plush_Nfet_30A_Tail EQU 62
  358. Turnigy_Plush_Nfet_30A_Multi EQU 63
  359. Turnigy_AE_20A_Main EQU 64
  360. Turnigy_AE_20A_Tail EQU 65
  361. Turnigy_AE_20A_Multi EQU 66
  362. Turnigy_AE_25A_Main EQU 67
  363. Turnigy_AE_25A_Tail EQU 68
  364. Turnigy_AE_25A_Multi EQU 69
  365. Turnigy_AE_30A_Main EQU 70
  366. Turnigy_AE_30A_Tail EQU 71
  367. Turnigy_AE_30A_Multi EQU 72
  368. Turnigy_AE_45A_Main EQU 73
  369. Turnigy_AE_45A_Tail EQU 74
  370. Turnigy_AE_45A_Multi EQU 75
  371. Turnigy_KForce_40A_Main EQU 76
  372. Turnigy_KForce_40A_Tail EQU 77
  373. Turnigy_KForce_40A_Multi EQU 78
  374. Turnigy_KForce_70A_HV_Main EQU 79
  375. Turnigy_KForce_70A_HV_Tail EQU 80
  376. Turnigy_KForce_70A_HV_Multi EQU 81
  377. Turnigy_KForce_120A_HV_Main EQU 82
  378. Turnigy_KForce_120A_HV_Tail EQU 83
  379. Turnigy_KForce_120A_HV_Multi EQU 84
  380. Turnigy_KForce_120A_HV_v2_Main EQU 85
  381. Turnigy_KForce_120A_HV_v2_Tail EQU 86
  382. Turnigy_KForce_120A_HV_v2_Multi EQU 87
  383. Skywalker_20A_Main EQU 88
  384. Skywalker_20A_Tail EQU 89
  385. Skywalker_20A_Multi EQU 90
  386. Skywalker_40A_Main EQU 91
  387. Skywalker_40A_Tail EQU 92
  388. Skywalker_40A_Multi EQU 93
  389. HiModel_Cool_22A_Main EQU 94
  390. HiModel_Cool_22A_Tail EQU 95
  391. HiModel_Cool_22A_Multi EQU 96
  392. HiModel_Cool_33A_Main EQU 97
  393. HiModel_Cool_33A_Tail EQU 98
  394. HiModel_Cool_33A_Multi EQU 99
  395. HiModel_Cool_41A_Main EQU 100
  396. HiModel_Cool_41A_Tail EQU 101
  397. HiModel_Cool_41A_Multi EQU 102
  398. RCTimer_6A_Main EQU 103
  399. RCTimer_6A_Tail EQU 104
  400. RCTimer_6A_Multi EQU 105
  401. Align_RCE_BL15X_Main EQU 106
  402. Align_RCE_BL15X_Tail EQU 107
  403. Align_RCE_BL15X_Multi EQU 108
  404. Align_RCE_BL15P_Main EQU 109
  405. Align_RCE_BL15P_Tail EQU 110
  406. Align_RCE_BL15P_Multi EQU 111
  407. Align_RCE_BL35X_Main EQU 112
  408. Align_RCE_BL35X_Tail EQU 113
  409. Align_RCE_BL35X_Multi EQU 114
  410. Align_RCE_BL35P_Main EQU 115
  411. Align_RCE_BL35P_Tail EQU 116
  412. Align_RCE_BL35P_Multi EQU 117
  413. Gaui_GE_183_18A_Main EQU 118
  414. Gaui_GE_183_18A_Tail EQU 119
  415. Gaui_GE_183_18A_Multi EQU 120
  416. H_King_10A_Main EQU 121
  417. H_King_10A_Tail EQU 122
  418. H_King_10A_Multi EQU 123
  419. H_King_20A_Main EQU 124
  420. H_King_20A_Tail EQU 125
  421. H_King_20A_Multi EQU 126
  422. H_King_35A_Main EQU 127
  423. H_King_35A_Tail EQU 128
  424. H_King_35A_Multi EQU 129
  425. H_King_50A_Main EQU 130
  426. H_King_50A_Tail EQU 131
  427. H_King_50A_Multi EQU 132
  428. Polaris_Thunder_12A_Main EQU 133
  429. Polaris_Thunder_12A_Tail EQU 134
  430. Polaris_Thunder_12A_Multi EQU 135
  431. Polaris_Thunder_20A_Main EQU 136
  432. Polaris_Thunder_20A_Tail EQU 137
  433. Polaris_Thunder_20A_Multi EQU 138
  434. Polaris_Thunder_30A_Main EQU 139
  435. Polaris_Thunder_30A_Tail EQU 140
  436. Polaris_Thunder_30A_Multi EQU 141
  437. Polaris_Thunder_40A_Main EQU 142
  438. Polaris_Thunder_40A_Tail EQU 143
  439. Polaris_Thunder_40A_Multi EQU 144
  440. Polaris_Thunder_60A_Main EQU 145
  441. Polaris_Thunder_60A_Tail EQU 146
  442. Polaris_Thunder_60A_Multi EQU 147
  443. Polaris_Thunder_80A_Main EQU 148
  444. Polaris_Thunder_80A_Tail EQU 149
  445. Polaris_Thunder_80A_Multi EQU 150
  446. Polaris_Thunder_100A_Main EQU 151
  447. Polaris_Thunder_100A_Tail EQU 152
  448. Polaris_Thunder_100A_Multi EQU 153
  449. Platinum_Pro_30A_Main EQU 154
  450. Platinum_Pro_30A_Tail EQU 155
  451. Platinum_Pro_30A_Multi EQU 156
  452. Platinum_Pro_150A_Main EQU 157
  453. Platinum_Pro_150A_Tail EQU 158
  454. Platinum_Pro_150A_Multi EQU 159
  455. Platinum_50Av3_Main EQU 160
  456. Platinum_50Av3_Tail EQU 161
  457. Platinum_50Av3_Multi EQU 162
  458. EAZY_3Av2_Main EQU 163
  459. EAZY_3Av2_Tail EQU 164
  460. EAZY_3Av2_Multi EQU 165
  461. Tarot_30A_Main EQU 166
  462. Tarot_30A_Tail EQU 167
  463. Tarot_30A_Multi EQU 168
  464. SkyIII_30A_Main EQU 169
  465. SkyIII_30A_Tail EQU 170
  466. SkyIII_30A_Multi EQU 171
  467. EMAX_20A_Main EQU 172
  468. EMAX_20A_Tail EQU 173
  469. EMAX_20A_Multi EQU 174
  470. EMAX_40A_Main EQU 175
  471. EMAX_40A_Tail EQU 176
  472. EMAX_40A_Multi EQU 177
  473. EMAX_Nano_20A_Main EQU 178
  474. EMAX_Nano_20A_Tail EQU 179
  475. EMAX_Nano_20A_Multi EQU 180
  476. EMAX_Lightning_20A_Main EQU 181
  477. EMAX_Lightning_20A_Tail EQU 182
  478. EMAX_Lightning_20A_Multi EQU 183
  479. XRotor_10A_Main EQU 184
  480. XRotor_10A_Tail EQU 185
  481. XRotor_10A_Multi EQU 186
  482. XRotor_20A_Main EQU 187
  483. XRotor_20A_Tail EQU 188
  484. XRotor_20A_Multi EQU 189
  485. XRotor_40A_Main EQU 190
  486. XRotor_40A_Tail EQU 191
  487. XRotor_40A_Multi EQU 192
  488. MDRX62H_Main EQU 193
  489. MDRX62H_Tail EQU 194
  490. MDRX62H_Multi EQU 195
  491. RotorGeeks_20A_Main EQU 196
  492. RotorGeeks_20A_Tail EQU 197
  493. RotorGeeks_20A_Multi EQU 198
  494. RotorGeeks_20A_Plus_Main EQU 199
  495. RotorGeeks_20A_Plus_Tail EQU 200
  496. RotorGeeks_20A_Plus_Multi EQU 201
  497. Flycolor_Fairy_6A_Main EQU 202
  498. Flycolor_Fairy_6A_Tail EQU 203
  499. Flycolor_Fairy_6A_Multi EQU 204
  500. Flycolor_Fairy_30A_Main EQU 205
  501. Flycolor_Fairy_30A_Tail EQU 206
  502. Flycolor_Fairy_30A_Multi EQU 207
  503. Flycolor_Fairy_V2_30A_Main EQU 208
  504. Flycolor_Fairy_V2_30A_Tail EQU 209
  505. Flycolor_Fairy_V2_30A_Multi EQU 210
  506. Flycolor_Raptor_20A_Main EQU 211
  507. Flycolor_Raptor_20A_Tail EQU 212
  508. Flycolor_Raptor_20A_Multi EQU 213
  509. Flycolor_Raptor_390_20A_Main EQU 214
  510. Flycolor_Raptor_390_20A_Tail EQU 215
  511. Flycolor_Raptor_390_20A_Multi EQU 216
  512. FVT_Littlebee_12A_Main EQU 217
  513. FVT_Littlebee_12A_Tail EQU 218
  514. FVT_Littlebee_12A_Multi EQU 219
  515. FVT_Littlebee_20A_Main EQU 220
  516. FVT_Littlebee_20A_Tail EQU 221
  517. FVT_Littlebee_20A_Multi EQU 222
  518. FVT_Littlebee_20A_Pro_Main EQU 223
  519. FVT_Littlebee_20A_Pro_Tail EQU 224
  520. FVT_Littlebee_20A_Pro_Multi EQU 225
  521. FVT_Littlebee_30A_Main EQU 226
  522. FVT_Littlebee_30A_Tail EQU 227
  523. FVT_Littlebee_30A_Multi EQU 228
  524. Graupner_Ultra_20A_Main EQU 229
  525. Graupner_Ultra_20A_Tail EQU 230
  526. Graupner_Ultra_20A_Multi EQU 231
  527. F85_3A_Main EQU 232
  528. F85_3A_Tail EQU 233
  529. F85_3A_Multi EQU 234
  530. ZTW_Spider_Pro_20A_Main EQU 235
  531. ZTW_Spider_Pro_20A_Tail EQU 236
  532. ZTW_Spider_Pro_20A_Multi EQU 237
  533. ZTW_Spider_Pro_20A_Premium_Main EQU 238
  534. ZTW_Spider_Pro_20A_Premium_Tail EQU 239
  535. ZTW_Spider_Pro_20A_Premium_Multi EQU 240
  536. ZTW_Spider_Pro_20A_HV_Main EQU 241
  537. ZTW_Spider_Pro_20A_HV_Tail EQU 242
  538. ZTW_Spider_Pro_20A_HV_Multi EQU 243
  539. ZTW_Spider_Pro_30A_HV_Main EQU 244
  540. ZTW_Spider_Pro_30A_HV_Tail EQU 245
  541. ZTW_Spider_Pro_30A_HV_Multi EQU 246
  542. DYS_XM20A_Main EQU 247
  543. DYS_XM20A_Tail EQU 248
  544. DYS_XM20A_Multi EQU 249
  545. Oversky_MR_20A_Main EQU 250
  546. Oversky_MR_20A_Tail EQU 251
  547. Oversky_MR_20A_Multi EQU 252
  548. Oversky_MR_20A_Pro_Main EQU 253
  549. Oversky_MR_20A_Pro_Tail EQU 254
  550. Oversky_MR_20A_Pro_Multi EQU 255
  551. TBS_Cube_12A_Main EQU 256
  552. TBS_Cube_12A_Tail EQU 257
  553. TBS_Cube_12A_Multi EQU 258
  554. DALRC_XR20A_Main EQU 259
  555. DALRC_XR20A_Tail EQU 260
  556. DALRC_XR20A_Multi EQU 261
  557. AIKON_Boltlite_30A_Main EQU 262
  558. AIKON_Boltlite_30A_Tail EQU 263
  559. AIKON_Boltlite_30A_Multi EQU 264
  560. Align_MR25_15A_Main EQU 265
  561. Align_MR25_15A_Tail EQU 266
  562. Align_MR25_15A_Multi EQU 267
  563. Servoking_Monster_30A_Main EQU 268
  564. Servoking_Monster_30A_Tail EQU 269
  565. Servoking_Monster_30A_Multi EQU 270
  566. Servoking_Monster_30A_Pro_Main EQU 271
  567. Servoking_Monster_30A_Pro_Tail EQU 272
  568. Servoking_Monster_30A_Pro_Multi EQU 273
  569. Servoking_Monster_70A_Pro_Main EQU 274
  570. Servoking_Monster_70A_Pro_Tail EQU 275
  571. Servoking_Monster_70A_Pro_Multi EQU 276
  572. Servoking_Monster_80A_Main EQU 277
  573. Servoking_Monster_80A_Tail EQU 278
  574. Servoking_Monster_80A_Multi EQU 279
  575. HTIRC_Hummingbird_12A_Main EQU 280
  576. HTIRC_Hummingbird_12A_Tail EQU 281
  577. HTIRC_Hummingbird_12A_Multi EQU 282
  578. HTIRC_Hummingbird_20A_Main EQU 283
  579. HTIRC_Hummingbird_20A_Tail EQU 284
  580. HTIRC_Hummingbird_20A_Multi EQU 285
  581. HTIRC_Hummingbird_30A_Pro_Main EQU 286
  582. HTIRC_Hummingbird_30A_Pro_Tail EQU 287
  583. HTIRC_Hummingbird_30A_Pro_Multi EQU 288
  584. ;**** **** **** **** ****
  585. ; Select the ESC and mode to use (or unselect all for use with external batch compile file)
  586. ;BESCNO EQU XP_3A_Main
  587. ;BESCNO EQU XP_3A_Tail
  588. ;BESCNO EQU XP_3A_Multi
  589. ;BESCNO EQU XP_7A_Main
  590. ;BESCNO EQU XP_7A_Tail
  591. ;BESCNO EQU XP_7A_Multi
  592. ;BESCNO EQU XP_7A_Fast_Main
  593. ;BESCNO EQU XP_7A_Fast_Tail
  594. ;BESCNO EQU XP_7A_Fast_Multi
  595. ;BESCNO EQU XP_12A_Main
  596. ;BESCNO EQU XP_12A_Tail
  597. ;BESCNO EQU XP_12A_Multi
  598. ;BESCNO EQU XP_18A_Main
  599. ;BESCNO EQU XP_18A_Tail
  600. ;BESCNO EQU XP_18A_Multi
  601. ;BESCNO EQU XP_25A_Main
  602. ;BESCNO EQU XP_25A_Tail
  603. ;BESCNO EQU XP_25A_Multi
  604. ;BESCNO EQU XP_35A_SW_Main
  605. ;BESCNO EQU XP_35A_SW_Tail
  606. ;BESCNO EQU XP_35A_SW_Multi
  607. ;BESCNO EQU DP_3A_Main
  608. ;BESCNO EQU DP_3A_Tail
  609. ;BESCNO EQU DP_3A_Multi
  610. ;BESCNO EQU Supermicro_3p5A_Main
  611. ;BESCNO EQU Supermicro_3p5A_Tail
  612. ;BESCNO EQU Supermicro_3p5A_Multi
  613. ;BESCNO EQU Turnigy_Plush_6A_Main
  614. ;BESCNO EQU Turnigy_Plush_6A_Tail
  615. ;BESCNO EQU Turnigy_Plush_6A_Multi
  616. ;BESCNO EQU Turnigy_Plush_10A_Main
  617. ;BESCNO EQU Turnigy_Plush_10A_Tail
  618. ;BESCNO EQU Turnigy_Plush_10A_Multi
  619. ;BESCNO EQU Turnigy_Plush_12A_Main
  620. ;BESCNO EQU Turnigy_Plush_12A_Tail
  621. ;BESCNO EQU Turnigy_Plush_12A_Multi
  622. ;BESCNO EQU Turnigy_Plush_18A_Main
  623. ;BESCNO EQU Turnigy_Plush_18A_Tail
  624. ;BESCNO EQU Turnigy_Plush_18A_Multi
  625. ;BESCNO EQU Turnigy_Plush_25A_Main
  626. ;BESCNO EQU Turnigy_Plush_25A_Tail
  627. ;BESCNO EQU Turnigy_Plush_25A_Multi
  628. ;BESCNO EQU Turnigy_Plush_30A_Main
  629. ;BESCNO EQU Turnigy_Plush_30A_Tail
  630. ;BESCNO EQU Turnigy_Plush_30A_Multi
  631. ;BESCNO EQU Turnigy_Plush_40A_Main
  632. ;BESCNO EQU Turnigy_Plush_40A_Tail
  633. ;BESCNO EQU Turnigy_Plush_40A_Multi
  634. ;BESCNO EQU Turnigy_Plush_60A_Main
  635. ;BESCNO EQU Turnigy_Plush_60A_Tail
  636. ;BESCNO EQU Turnigy_Plush_60A_Multi
  637. ;BESCNO EQU Turnigy_Plush_80A_Main
  638. ;BESCNO EQU Turnigy_Plush_80A_Tail
  639. ;BESCNO EQU Turnigy_Plush_80A_Multi
  640. ;BESCNO EQU Turnigy_Plush_Nfet_18A_Main
  641. ;BESCNO EQU Turnigy_Plush_Nfet_18A_Tail
  642. ;BESCNO EQU Turnigy_Plush_Nfet_18A_Multi
  643. ;BESCNO EQU Turnigy_Plush_Nfet_25A_Main
  644. ;BESCNO EQU Turnigy_Plush_Nfet_25A_Tail
  645. ;BESCNO EQU Turnigy_Plush_Nfet_25A_Multi
  646. ;BESCNO EQU Turnigy_Plush_Nfet_30A_Main
  647. ;BESCNO EQU Turnigy_Plush_Nfet_30A_Tail
  648. ;BESCNO EQU Turnigy_Plush_Nfet_30A_Multi
  649. ;BESCNO EQU Turnigy_AE_20A_Main
  650. ;BESCNO EQU Turnigy_AE_20A_Tail
  651. ;BESCNO EQU Turnigy_AE_20A_Multi
  652. ;BESCNO EQU Turnigy_AE_25A_Main
  653. ;BESCNO EQU Turnigy_AE_25A_Tail
  654. ;BESCNO EQU Turnigy_AE_25A_Multi
  655. ;BESCNO EQU Turnigy_AE_30A_Main
  656. ;BESCNO EQU Turnigy_AE_30A_Tail
  657. ;BESCNO EQU Turnigy_AE_30A_Multi
  658. ;BESCNO EQU Turnigy_AE_45A_Main
  659. ;BESCNO EQU Turnigy_AE_45A_Tail
  660. ;BESCNO EQU Turnigy_AE_45A_Multi
  661. ;BESCNO EQU Turnigy_KForce_40A_Main
  662. ;BESCNO EQU Turnigy_KForce_40A_Tail
  663. ;BESCNO EQU Turnigy_KForce_40A_Multi
  664. ;BESCNO EQU Turnigy_KForce_70A_HV_Main
  665. ;BESCNO EQU Turnigy_KForce_70A_HV_Tail
  666. ;BESCNO EQU Turnigy_KForce_70A_HV_Multi
  667. ;BESCNO EQU Turnigy_KForce_120A_HV_Main
  668. ;BESCNO EQU Turnigy_KForce_120A_HV_Tail
  669. ;BESCNO EQU Turnigy_KForce_120A_HV_Multi
  670. ;BESCNO EQU Turnigy_KForce_120A_HV_v2_Main
  671. ;BESCNO EQU Turnigy_KForce_120A_HV_v2_Tail
  672. ;BESCNO EQU Turnigy_KForce_120A_HV_v2_Multi
  673. ;BESCNO EQU Skywalker_20A_Main
  674. ;BESCNO EQU Skywalker_20A_Tail
  675. ;BESCNO EQU Skywalker_20A_Multi
  676. ;BESCNO EQU Skywalker_40A_Main
  677. ;BESCNO EQU Skywalker_40A_Tail
  678. ;BESCNO EQU Skywalker_40A_Multi
  679. ;BESCNO EQU HiModel_Cool_22A_Main
  680. ;BESCNO EQU HiModel_Cool_22A_Tail
  681. ;BESCNO EQU HiModel_Cool_22A_Multi
  682. ;BESCNO EQU HiModel_Cool_33A_Main
  683. ;BESCNO EQU HiModel_Cool_33A_Tail
  684. ;BESCNO EQU HiModel_Cool_33A_Multi
  685. ;BESCNO EQU HiModel_Cool_41A_Main
  686. ;BESCNO EQU HiModel_Cool_41A_Tail
  687. ;BESCNO EQU HiModel_Cool_41A_Multi
  688. ;BESCNO EQU RCTimer_6A_Main
  689. ;BESCNO EQU RCTimer_6A_Tail
  690. ;BESCNO EQU RCTimer_6A_Multi
  691. ;BESCNO EQU Align_RCE_BL15X_Main
  692. ;BESCNO EQU Align_RCE_BL15X_Tail
  693. ;BESCNO EQU Align_RCE_BL15X_Multi
  694. ;BESCNO EQU Align_RCE_BL15P_Main
  695. ;BESCNO EQU Align_RCE_BL15P_Tail
  696. ;BESCNO EQU Align_RCE_BL15P_Multi
  697. ;BESCNO EQU Align_RCE_BL35X_Main
  698. ;BESCNO EQU Align_RCE_BL35X_Tail
  699. ;BESCNO EQU Align_RCE_BL35X_Multi
  700. ;BESCNO EQU Align_RCE_BL35P_Main
  701. ;BESCNO EQU Align_RCE_BL35P_Tail
  702. ;BESCNO EQU Align_RCE_BL35P_Multi
  703. ;BESCNO EQU Gaui_GE_183_18A_Main
  704. ;BESCNO EQU Gaui_GE_183_18A_Tail
  705. ;BESCNO EQU Gaui_GE_183_18A_Multi
  706. ;BESCNO EQU H_King_10A_Main
  707. ;BESCNO EQU H_King_10A_Tail
  708. ;BESCNO EQU H_King_10A_Multi
  709. ;BESCNO EQU H_King_20A_Main
  710. ;BESCNO EQU H_King_20A_Tail
  711. ;BESCNO EQU H_King_20A_Multi
  712. ;BESCNO EQU H_King_35A_Main
  713. ;BESCNO EQU H_King_35A_Tail
  714. ;BESCNO EQU H_King_35A_Multi
  715. ;BESCNO EQU H_King_50A_Main
  716. ;BESCNO EQU H_King_50A_Tail
  717. ;BESCNO EQU H_King_50A_Multi
  718. ;BESCNO EQU Polaris_Thunder_12A_Main
  719. ;BESCNO EQU Polaris_Thunder_12A_Tail
  720. ;BESCNO EQU Polaris_Thunder_12A_Multi
  721. ;BESCNO EQU Polaris_Thunder_20A_Main
  722. ;BESCNO EQU Polaris_Thunder_20A_Tail
  723. ;BESCNO EQU Polaris_Thunder_20A_Multi
  724. ;BESCNO EQU Polaris_Thunder_30A_Main
  725. ;BESCNO EQU Polaris_Thunder_30A_Tail
  726. ;BESCNO EQU Polaris_Thunder_30A_Multi
  727. ;BESCNO EQU Polaris_Thunder_40A_Main
  728. ;BESCNO EQU Polaris_Thunder_40A_Tail
  729. ;BESCNO EQU Polaris_Thunder_40A_Multi
  730. ;BESCNO EQU Polaris_Thunder_60A_Main
  731. ;BESCNO EQU Polaris_Thunder_60A_Tail
  732. ;BESCNO EQU Polaris_Thunder_60A_Multi
  733. ;BESCNO EQU Polaris_Thunder_80A_Main
  734. ;BESCNO EQU Polaris_Thunder_80A_Tail
  735. ;BESCNO EQU Polaris_Thunder_80A_Multi
  736. ;BESCNO EQU Polaris_Thunder_100A_Main
  737. ;BESCNO EQU Polaris_Thunder_100A_Tail
  738. ;BESCNO EQU Polaris_Thunder_100A_Multi
  739. ;BESCNO EQU Platinum_Pro_30A_Main
  740. ;BESCNO EQU Platinum_Pro_30A_Tail
  741. ;BESCNO EQU Platinum_Pro_30A_Multi
  742. ;BESCNO EQU Platinum_Pro_150A_Main
  743. ;BESCNO EQU Platinum_Pro_150A_Tail
  744. ;BESCNO EQU Platinum_Pro_150A_Multi
  745. ;BESCNO EQU Platinum_50Av3_Main
  746. ;BESCNO EQU Platinum_50Av3_Tail
  747. ;BESCNO EQU Platinum_50Av3_Multi
  748. ;BESCNO EQU EAZY_3Av2_Main
  749. ;BESCNO EQU EAZY_3Av2_Tail
  750. ;BESCNO EQU EAZY_3Av2_Multi
  751. ;BESCNO EQU Tarot_30A_Main
  752. ;BESCNO EQU Tarot_30A_Tail
  753. ;BESCNO EQU Tarot_30A_Multi
  754. ;BESCNO EQU SkyIII_30A_Main
  755. ;BESCNO EQU SkyIII_30A_Tail
  756. ;BESCNO EQU SkyIII_30A_Multi
  757. ;BESCNO EQU EMAX_20A_Main
  758. ;BESCNO EQU EMAX_20A_Tail
  759. ;BESCNO EQU EMAX_20A_Multi
  760. ;BESCNO EQU EMAX_40A_Main
  761. ;BESCNO EQU EMAX_40A_Tail
  762. ;BESCNO EQU EMAX_40A_Multi
  763. ;BESCNO EQU EMAX_Nano_20A_Main
  764. ;BESCNO EQU EMAX_Nano_20A_Tail
  765. ;BESCNO EQU EMAX_Nano_20A_Multi
  766. ;BESCNO EQU EMAX_Lightning_20A_Main
  767. ;BESCNO EQU EMAX_Lightning_20A_Tail
  768. ;BESCNO EQU EMAX_Lightning_20A_Multi
  769. ;BESCNO EQU XRotor_10A_Main
  770. ;BESCNO EQU XRotor_10A_Tail
  771. ;BESCNO EQU XRotor_10A_Multi
  772. ;BESCNO EQU XRotor_20A_Main
  773. ;BESCNO EQU XRotor_20A_Tail
  774. ;BESCNO EQU XRotor_20A_Multi
  775. ;BESCNO EQU XRotor_40A_Main
  776. ;BESCNO EQU XRotor_40A_Tail
  777. ;BESCNO EQU XRotor_40A_Multi
  778. ;BESCNO EQU MDRX62H_Main
  779. ;BESCNO EQU MDRX62H_Tail
  780. ;BESCNO EQU MDRX62H_Multi
  781. ;BESCNO EQU RotorGeeks_20A_Main
  782. ;BESCNO EQU RotorGeeks_20A_Tail
  783. ;BESCNO EQU RotorGeeks_20A_Multi
  784. ;BESCNO EQU RotorGeeks_20A_Plus_Main
  785. ;BESCNO EQU RotorGeeks_20A_Plus_Tail
  786. ;BESCNO EQU RotorGeeks_20A_Plus_Multi
  787. ;BESCNO EQU Flycolor_Fairy_6A_Main
  788. ;BESCNO EQU Flycolor_Fairy_6A_Tail
  789. ;BESCNO EQU Flycolor_Fairy_6A_Multi
  790. ;BESCNO EQU Flycolor_Fairy_30A_Main
  791. ;BESCNO EQU Flycolor_Fairy_30A_Tail
  792. ;BESCNO EQU Flycolor_Fairy_30A_Multi
  793. ;BESCNO EQU Flycolor_Fairy_V2_30A_Main
  794. ;BESCNO EQU Flycolor_Fairy_V2_30A_Tail
  795. ;BESCNO EQU Flycolor_Fairy_V2_30A_Multi
  796. ;BESCNO EQU Flycolor_Raptor_20A_Main
  797. ;BESCNO EQU Flycolor_Raptor_20A_Tail
  798. ;BESCNO EQU Flycolor_Raptor_20A_Multi
  799. ;BESCNO EQU Flycolor_Raptor_390_20A_Main
  800. ;BESCNO EQU Flycolor_Raptor_390_20A_Tail
  801. ;BESCNO EQU Flycolor_Raptor_390_20A_Multi
  802. ;BESCNO EQU FVT_Littlebee_12A_Main
  803. ;BESCNO EQU FVT_Littlebee_12A_Tail
  804. ;BESCNO EQU FVT_Littlebee_12A_Multi
  805. ;BESCNO EQU FVT_Littlebee_20A_Main
  806. ;BESCNO EQU FVT_Littlebee_20A_Tail
  807. ;BESCNO EQU FVT_Littlebee_20A_Multi
  808. ;BESCNO EQU FVT_Littlebee_20A_Pro_Main
  809. ;BESCNO EQU FVT_Littlebee_20A_Pro_Tail
  810. ;BESCNO EQU FVT_Littlebee_20A_Pro_Multi
  811. ;BESCNO EQU FVT_Littlebee_30A_Main
  812. ;BESCNO EQU FVT_Littlebee_30A_Tail
  813. ;BESCNO EQU FVT_Littlebee_30A_Multi
  814. ;BESCNO EQU Graupner_Ultra_20A_Main
  815. ;BESCNO EQU Graupner_Ultra_20A_Tail
  816. ;BESCNO EQU Graupner_Ultra_20A_Multi
  817. ;BESCNO EQU F85_3A_Main
  818. ;BESCNO EQU F85_3A_Tail
  819. ;BESCNO EQU F85_3A_Multi
  820. ;BESCNO EQU ZTW_Spider_Pro_20A_Main
  821. ;BESCNO EQU ZTW_Spider_Pro_20A_Tail
  822. ;BESCNO EQU ZTW_Spider_Pro_20A_Multi
  823. ;BESCNO EQU ZTW_Spider_Pro_20A_Premium_Main
  824. ;BESCNO EQU ZTW_Spider_Pro_20A_Premium_Tail
  825. ;BESCNO EQU ZTW_Spider_Pro_20A_Premium_Multi
  826. ;BESCNO EQU ZTW_Spider_Pro_20A_HV_Main
  827. ;BESCNO EQU ZTW_Spider_Pro_20A_HV_Tail
  828. ;BESCNO EQU ZTW_Spider_Pro_20A_HV_Multi
  829. ;BESCNO EQU ZTW_Spider_Pro_30A_HV_Main
  830. ;BESCNO EQU ZTW_Spider_Pro_30A_HV_Tail
  831. ;BESCNO EQU ZTW_Spider_Pro_30A_HV_Multi
  832. ;BESCNO EQU DYS_XM20A_Main
  833. ;BESCNO EQU DYS_XM20A_Tail
  834. ;BESCNO EQU DYS_XM20A_Multi
  835. ;BESCNO EQU Oversky_MR_20A_Main
  836. ;BESCNO EQU Oversky_MR_20A_Tail
  837. ;BESCNO EQU Oversky_MR_20A_Multi
  838. ;BESCNO EQU Oversky_MR_20A_Pro_Main
  839. ;BESCNO EQU Oversky_MR_20A_Pro_Tail
  840. ;BESCNO EQU Oversky_MR_20A_Pro_Multi
  841. ;BESCNO EQU TBS_Cube_12A_Main
  842. ;BESCNO EQU TBS_Cube_12A_Tail
  843. ;BESCNO EQU TBS_Cube_12A_Multi
  844. ;BESCNO EQU DALRC_XR20A_Main
  845. ;BESCNO EQU DALRC_XR20A_Tail
  846. ;BESCNO EQU DALRC_XR20A_Multi
  847. ;BESCNO EQU AIKON_Boltlite_30A_Main
  848. ;BESCNO EQU AIKON_Boltlite_30A_Tail
  849. ;BESCNO EQU AIKON_Boltlite_30A_Multi
  850. ;BESCNO EQU Align_MR25_15A_Main
  851. ;BESCNO EQU Align_MR25_15A_Tail
  852. ;BESCNO EQU Align_MR25_15A_Multi
  853. ;BESCNO EQU Servoking_Monster_30A_Main
  854. ;BESCNO EQU Servoking_Monster_30A_Tail
  855. ;BESCNO EQU Servoking_Monster_30A_Multi
  856. ;BESCNO EQU Servoking_Monster_30A_Pro_Main
  857. ;BESCNO EQU Servoking_Monster_30A_Pro_Tail
  858. ;BESCNO EQU Servoking_Monster_30A_Pro_Multi
  859. ;BESCNO EQU Servoking_Monster_70A_Pro_Main
  860. ;BESCNO EQU Servoking_Monster_70A_Pro_Tail
  861. ;BESCNO EQU Servoking_Monster_70A_Pro_Multi
  862. ;BESCNO EQU Servoking_Monster_80A_Main
  863. ;BESCNO EQU Servoking_Monster_80A_Tail
  864. ;BESCNO EQU Servoking_Monster_80A_Multi
  865. ;BESCNO EQU HTIRC_Hummingbird_12A_Main
  866. ;BESCNO EQU HTIRC_Hummingbird_12A_Tail
  867. ;BESCNO EQU HTIRC_Hummingbird_12A_Multi
  868. ;BESCNO EQU HTIRC_Hummingbird_20A_Main
  869. ;BESCNO EQU HTIRC_Hummingbird_20A_Tail
  870. ;BESCNO EQU HTIRC_Hummingbird_20A_Multi
  871. ;BESCNO EQU HTIRC_Hummingbird_30A_Pro_Main
  872. ;BESCNO EQU HTIRC_Hummingbird_30A_Pro_Tail
  873. ;BESCNO EQU HTIRC_Hummingbird_30A_Pro_Multi
  874. ;**** **** **** **** ****
  875. ; ESC selection statements
  876. IF BESCNO == XP_3A_Main
  877. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  878. $include (XP_3A.inc) ; Select XP 3A pinout
  879. ENDIF
  880. IF BESCNO == XP_3A_Tail
  881. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  882. $include (XP_3A.inc) ; Select XP 3A pinout
  883. ENDIF
  884. IF BESCNO == XP_3A_Multi
  885. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  886. $include (XP_3A.inc) ; Select XP 3A pinout
  887. ENDIF
  888. IF BESCNO == XP_7A_Main
  889. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  890. $include (XP_7A.inc) ; Select XP 7A pinout
  891. ENDIF
  892. IF BESCNO == XP_7A_Tail
  893. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  894. $include (XP_7A.inc) ; Select XP 7A pinout
  895. ENDIF
  896. IF BESCNO == XP_7A_Multi
  897. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  898. $include (XP_7A.inc) ; Select XP 7A pinout
  899. ENDIF
  900. IF BESCNO == XP_7A_Fast_Main
  901. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  902. $include (XP_7A_Fast.inc) ; Select XP 7A Fast pinout
  903. ENDIF
  904. IF BESCNO == XP_7A_Fast_Tail
  905. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  906. $include (XP_7A_Fast.inc) ; Select XP 7A Fast pinout
  907. ENDIF
  908. IF BESCNO == XP_7A_Fast_Multi
  909. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  910. $include (XP_7A_Fast.inc) ; Select XP 7A Fast pinout
  911. ENDIF
  912. IF BESCNO == XP_12A_Main
  913. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  914. $include (XP_12A.inc) ; Select XP 12A pinout
  915. ENDIF
  916. IF BESCNO == XP_12A_Tail
  917. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  918. $include (XP_12A.inc) ; Select XP 12A pinout
  919. ENDIF
  920. IF BESCNO == XP_12A_Multi
  921. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  922. $include (XP_12A.inc) ; Select XP 12A pinout
  923. ENDIF
  924. IF BESCNO == XP_18A_Main
  925. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  926. $include (XP_18A.inc) ; Select XP 18A pinout
  927. ENDIF
  928. IF BESCNO == XP_18A_Tail
  929. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  930. $include (XP_18A.inc) ; Select XP 18A pinout
  931. ENDIF
  932. IF BESCNO == XP_18A_Multi
  933. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  934. $include (XP_18A.inc) ; Select XP 18A pinout
  935. ENDIF
  936. IF BESCNO == XP_25A_Main
  937. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  938. $include (XP_25A.inc) ; Select XP 25A pinout
  939. ENDIF
  940. IF BESCNO == XP_25A_Tail
  941. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  942. $include (XP_25A.inc) ; Select XP 25A pinout
  943. ENDIF
  944. IF BESCNO == XP_25A_Multi
  945. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  946. $include (XP_25A.inc) ; Select XP 25A pinout
  947. ENDIF
  948. IF BESCNO == XP_35A_SW_Main
  949. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  950. $include (XP_35A_SW.inc) ; Select XP 35A SW pinout
  951. ENDIF
  952. IF BESCNO == XP_35A_SW_Tail
  953. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  954. $include (XP_35A_SW.inc) ; Select XP 35A SW pinout
  955. ENDIF
  956. IF BESCNO == XP_35A_SW_Multi
  957. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  958. $include (XP_35A_SW.inc) ; Select XP 35A SW pinout
  959. ENDIF
  960. IF BESCNO == DP_3A_Main
  961. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  962. $include (DP_3A.inc) ; Select DP 3A pinout
  963. ENDIF
  964. IF BESCNO == DP_3A_Tail
  965. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  966. $include (DP_3A.inc) ; Select DP 3A pinout
  967. ENDIF
  968. IF BESCNO == DP_3A_Multi
  969. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  970. $include (DP_3A.inc) ; Select DP 3A pinout
  971. ENDIF
  972. IF BESCNO == Supermicro_3p5A_Main
  973. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  974. $include (Supermicro_3p5A.inc) ; Select Supermicro 3.5A pinout
  975. ENDIF
  976. IF BESCNO == Supermicro_3p5A_Tail
  977. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  978. $include (Supermicro_3p5A.inc) ; Select Supermicro 3.5A pinout
  979. ENDIF
  980. IF BESCNO == Supermicro_3p5A_Multi
  981. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  982. $include (Supermicro_3p5A.inc) ; Select Supermicro 3.5A pinout
  983. ENDIF
  984. IF BESCNO == Turnigy_Plush_6A_Main
  985. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  986. $include (Turnigy_Plush_6A.inc) ; Select Turnigy Plush 6A pinout
  987. ENDIF
  988. IF BESCNO == Turnigy_Plush_6A_Tail
  989. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  990. $include (Turnigy_Plush_6A.inc) ; Select Turnigy Plush 6A pinout
  991. ENDIF
  992. IF BESCNO == Turnigy_Plush_6A_Multi
  993. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  994. $include (Turnigy_Plush_6A.inc) ; Select Turnigy Plush 6A pinout
  995. ENDIF
  996. IF BESCNO == Turnigy_Plush_10A_Main
  997. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  998. $include (Turnigy_Plush_10A.inc) ; Select Turnigy Plush 10A pinout
  999. ENDIF
  1000. IF BESCNO == Turnigy_Plush_10A_Tail
  1001. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1002. $include (Turnigy_Plush_10A.inc) ; Select Turnigy Plush 10A pinout
  1003. ENDIF
  1004. IF BESCNO == Turnigy_Plush_10A_Multi
  1005. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1006. $include (Turnigy_Plush_10A.inc) ; Select Turnigy Plush 10A pinout
  1007. ENDIF
  1008. IF BESCNO == Turnigy_Plush_12A_Main
  1009. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1010. $include (Turnigy_Plush_12A.inc) ; Select Turnigy Plush 12A pinout
  1011. ENDIF
  1012. IF BESCNO == Turnigy_Plush_12A_Tail
  1013. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1014. $include (Turnigy_Plush_12A.inc) ; Select Turnigy Plush 12A pinout
  1015. ENDIF
  1016. IF BESCNO == Turnigy_Plush_12A_Multi
  1017. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1018. $include (Turnigy_Plush_12A.inc) ; Select Turnigy Plush 12A pinout
  1019. ENDIF
  1020. IF BESCNO == Turnigy_Plush_18A_Main
  1021. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1022. $include (Turnigy_Plush_18A.inc) ; Select Turnigy Plush 18A pinout
  1023. ENDIF
  1024. IF BESCNO == Turnigy_Plush_18A_Tail
  1025. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1026. $include (Turnigy_Plush_18A.inc) ; Select Turnigy Plush 18A pinout
  1027. ENDIF
  1028. IF BESCNO == Turnigy_Plush_18A_Multi
  1029. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1030. $include (Turnigy_Plush_18A.inc) ; Select Turnigy Plush 18A pinout
  1031. ENDIF
  1032. IF BESCNO == Turnigy_Plush_25A_Main
  1033. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1034. $include (Turnigy_Plush_25A.inc) ; Select Turnigy Plush 25A pinout
  1035. ENDIF
  1036. IF BESCNO == Turnigy_Plush_25A_Tail
  1037. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1038. $include (Turnigy_Plush_25A.inc) ; Select Turnigy Plush 25A pinout
  1039. ENDIF
  1040. IF BESCNO == Turnigy_Plush_25A_Multi
  1041. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1042. $include (Turnigy_Plush_25A.inc) ; Select Turnigy Plush 25A pinout
  1043. ENDIF
  1044. IF BESCNO == Turnigy_Plush_30A_Main
  1045. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1046. $include (Turnigy_Plush_30A.inc) ; Select Turnigy Plush 30A pinout
  1047. ENDIF
  1048. IF BESCNO == Turnigy_Plush_30A_Tail
  1049. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1050. $include (Turnigy_Plush_30A.inc) ; Select Turnigy Plush 30A pinout
  1051. ENDIF
  1052. IF BESCNO == Turnigy_Plush_30A_Multi
  1053. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1054. $include (Turnigy_Plush_30A.inc) ; Select Turnigy Plush 30A pinout
  1055. ENDIF
  1056. IF BESCNO == Turnigy_Plush_40A_Main
  1057. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1058. $include (Turnigy_Plush_40A.inc) ; Select Turnigy Plush 40A pinout
  1059. ENDIF
  1060. IF BESCNO == Turnigy_Plush_40A_Tail
  1061. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1062. $include (Turnigy_Plush_40A.inc) ; Select Turnigy Plush 40A pinout
  1063. ENDIF
  1064. IF BESCNO == Turnigy_Plush_40A_Multi
  1065. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1066. $include (Turnigy_Plush_40A.inc) ; Select Turnigy Plush 40A pinout
  1067. ENDIF
  1068. IF BESCNO == Turnigy_Plush_60A_Main
  1069. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1070. $include (Turnigy_Plush_60A.inc) ; Select Turnigy Plush 60A pinout
  1071. ENDIF
  1072. IF BESCNO == Turnigy_Plush_60A_Tail
  1073. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1074. $include (Turnigy_Plush_60A.inc) ; Select Turnigy Plush 60A pinout
  1075. ENDIF
  1076. IF BESCNO == Turnigy_Plush_60A_Multi
  1077. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1078. $include (Turnigy_Plush_60A.inc) ; Select Turnigy Plush 60A pinout
  1079. ENDIF
  1080. IF BESCNO == Turnigy_Plush_80A_Main
  1081. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1082. $include (Turnigy_Plush_80A.inc) ; Select Turnigy Plush 80A pinout
  1083. ENDIF
  1084. IF BESCNO == Turnigy_Plush_80A_Tail
  1085. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1086. $include (Turnigy_Plush_80A.inc) ; Select Turnigy Plush 80A pinout
  1087. ENDIF
  1088. IF BESCNO == Turnigy_Plush_80A_Multi
  1089. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1090. $include (Turnigy_Plush_80A.inc) ; Select Turnigy Plush 80A pinout
  1091. ENDIF
  1092. IF BESCNO == Turnigy_Plush_Nfet_18A_Main
  1093. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1094. $include (Turnigy_Plush_Nfet_18A.inc) ; Select Turnigy Plush Nfet 18A pinout
  1095. ENDIF
  1096. IF BESCNO == Turnigy_Plush_Nfet_18A_Tail
  1097. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1098. $include (Turnigy_Plush_Nfet_18A.inc) ; Select Turnigy Plush Nfet 18A pinout
  1099. ENDIF
  1100. IF BESCNO == Turnigy_Plush_Nfet_18A_Multi
  1101. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1102. $include (Turnigy_Plush_Nfet_18A.inc) ; Select Turnigy Plush Nfet 18A pinout
  1103. ENDIF
  1104. IF BESCNO == Turnigy_Plush_Nfet_25A_Main
  1105. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1106. $include (Turnigy_Plush_Nfet_25A.inc) ; Select Turnigy Plush Nfet 25A pinout
  1107. ENDIF
  1108. IF BESCNO == Turnigy_Plush_Nfet_25A_Tail
  1109. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1110. $include (Turnigy_Plush_Nfet_25A.inc) ; Select Turnigy Plush Nfet 25A pinout
  1111. ENDIF
  1112. IF BESCNO == Turnigy_Plush_Nfet_25A_Multi
  1113. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1114. $include (Turnigy_Plush_Nfet_25A.inc) ; Select Turnigy Plush Nfet 25A pinout
  1115. ENDIF
  1116. IF BESCNO == Turnigy_Plush_Nfet_30A_Main
  1117. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1118. $include (Turnigy_Plush_Nfet_30A.inc) ; Select Turnigy Plush Nfet 30A pinout
  1119. ENDIF
  1120. IF BESCNO == Turnigy_Plush_Nfet_30A_Tail
  1121. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1122. $include (Turnigy_Plush_Nfet_30A.inc) ; Select Turnigy Plush Nfet 30A pinout
  1123. ENDIF
  1124. IF BESCNO == Turnigy_Plush_Nfet_30A_Multi
  1125. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1126. $include (Turnigy_Plush_Nfet_30A.inc) ; Select Turnigy Plush Nfet 30A pinout
  1127. ENDIF
  1128. IF BESCNO == Turnigy_AE_20A_Main
  1129. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1130. $include (Turnigy_AE_20A.inc) ; Select Turnigy AE-20A pinout
  1131. ENDIF
  1132. IF BESCNO == Turnigy_AE_20A_Tail
  1133. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1134. $include (Turnigy_AE_20A.inc) ; Select Turnigy AE-20A pinout
  1135. ENDIF
  1136. IF BESCNO == Turnigy_AE_20A_Multi
  1137. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1138. $include (Turnigy_AE_20A.inc) ; Select Turnigy AE-20A pinout
  1139. ENDIF
  1140. IF BESCNO == Turnigy_AE_25A_Main
  1141. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1142. $include (Turnigy_AE_25A.inc) ; Select Turnigy AE-25A pinout
  1143. ENDIF
  1144. IF BESCNO == Turnigy_AE_25A_Tail
  1145. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1146. $include (Turnigy_AE_25A.inc) ; Select Turnigy AE-25A pinout
  1147. ENDIF
  1148. IF BESCNO == Turnigy_AE_25A_Multi
  1149. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1150. $include (Turnigy_AE_25A.inc) ; Select Turnigy AE-25A pinout
  1151. ENDIF
  1152. IF BESCNO == Turnigy_AE_30A_Main
  1153. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1154. $include (Turnigy_AE_30A.inc) ; Select Turnigy AE-30A pinout
  1155. ENDIF
  1156. IF BESCNO == Turnigy_AE_30A_Tail
  1157. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1158. $include (Turnigy_AE_30A.inc) ; Select Turnigy AE-30A pinout
  1159. ENDIF
  1160. IF BESCNO == Turnigy_AE_30A_Multi
  1161. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1162. $include (Turnigy_AE_30A.inc) ; Select Turnigy AE-30A pinout
  1163. ENDIF
  1164. IF BESCNO == Turnigy_AE_45A_Main
  1165. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1166. $include (Turnigy_AE_45A.inc) ; Select Turnigy AE-45A pinout
  1167. ENDIF
  1168. IF BESCNO == Turnigy_AE_45A_Tail
  1169. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1170. $include (Turnigy_AE_45A.inc) ; Select Turnigy AE-45A pinout
  1171. ENDIF
  1172. IF BESCNO == Turnigy_AE_45A_Multi
  1173. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1174. $include (Turnigy_AE_45A.inc) ; Select Turnigy AE-45A pinout
  1175. ENDIF
  1176. IF BESCNO == Turnigy_KForce_40A_Main
  1177. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1178. $include (Turnigy_KForce_40A.inc) ; Select Turnigy KForce 40A pinout
  1179. ENDIF
  1180. IF BESCNO == Turnigy_KForce_40A_Tail
  1181. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1182. $include (Turnigy_KForce_40A.inc) ; Select Turnigy KForce 40A pinout
  1183. ENDIF
  1184. IF BESCNO == Turnigy_KForce_40A_Multi
  1185. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1186. $include (Turnigy_KForce_40A.inc) ; Select Turnigy KForce 40A pinout
  1187. ENDIF
  1188. IF BESCNO == Turnigy_KForce_70A_HV_Main
  1189. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1190. $include (Turnigy_KForce_70A_HV.inc) ; Select Turnigy KForce 70A HV pinout
  1191. ENDIF
  1192. IF BESCNO == Turnigy_KForce_70A_HV_Tail
  1193. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1194. $include (Turnigy_KForce_70A_HV.inc) ; Select Turnigy KForce 70A HV pinout
  1195. ENDIF
  1196. IF BESCNO == Turnigy_KForce_70A_HV_Multi
  1197. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1198. $include (Turnigy_KForce_70A_HV.inc) ; Select Turnigy KForce 70A HV pinout
  1199. ENDIF
  1200. IF BESCNO == Turnigy_KForce_120A_HV_Main
  1201. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1202. $include (Turnigy_KForce_120A_HV.inc) ; Select Turnigy KForce 120A HV pinout
  1203. ENDIF
  1204. IF BESCNO == Turnigy_KForce_120A_HV_Tail
  1205. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1206. $include (Turnigy_KForce_120A_HV.inc) ; Select Turnigy KForce 120A HV pinout
  1207. ENDIF
  1208. IF BESCNO == Turnigy_KForce_120A_HV_Multi
  1209. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1210. $include (Turnigy_KForce_120A_HV.inc) ; Select Turnigy KForce 120A HV pinout
  1211. ENDIF
  1212. IF BESCNO == Turnigy_KForce_120A_HV_v2_Main
  1213. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1214. $include (Turnigy_KForce_120A_HV_v2.inc); Select Turnigy KForce 120A HV v2 pinout
  1215. ENDIF
  1216. IF BESCNO == Turnigy_KForce_120A_HV_v2_Tail
  1217. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1218. $include (Turnigy_KForce_120A_HV_v2.inc); Select Turnigy KForce 120A HV v2 pinout
  1219. ENDIF
  1220. IF BESCNO == Turnigy_KForce_120A_HV_v2_Multi
  1221. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1222. $include (Turnigy_KForce_120A_HV_v2.inc); Select Turnigy KForce 120A HV v2 pinout
  1223. ENDIF
  1224. IF BESCNO == Skywalker_20A_Main
  1225. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1226. $include (Skywalker_20A.inc) ; Select Skywalker 20A pinout
  1227. ENDIF
  1228. IF BESCNO == Skywalker_20A_Tail
  1229. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1230. $include (Skywalker_20A.inc) ; Select Skywalker 20A pinout
  1231. ENDIF
  1232. IF BESCNO == Skywalker_20A_Multi
  1233. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1234. $include (Skywalker_20A.inc) ; Select Skywalker 20A pinout
  1235. ENDIF
  1236. IF BESCNO == Skywalker_40A_Main
  1237. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1238. $include (Skywalker_40A.inc) ; Select Skywalker 40A pinout
  1239. ENDIF
  1240. IF BESCNO == Skywalker_40A_Tail
  1241. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1242. $include (Skywalker_40A.inc) ; Select Skywalker 40A pinout
  1243. ENDIF
  1244. IF BESCNO == Skywalker_40A_Multi
  1245. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1246. $include (Skywalker_40A.inc) ; Select Skywalker 40A pinout
  1247. ENDIF
  1248. IF BESCNO == HiModel_Cool_22A_Main
  1249. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1250. $include (HiModel_Cool_22A.inc) ; Select HiModel Cool 22A pinout
  1251. ENDIF
  1252. IF BESCNO == HiModel_Cool_22A_Tail
  1253. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1254. $include (HiModel_Cool_22A.inc) ; Select HiModel Cool 22A pinout
  1255. ENDIF
  1256. IF BESCNO == HiModel_Cool_22A_Multi
  1257. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1258. $include (HiModel_Cool_22A.inc) ; Select HiModel Cool 22A pinout
  1259. ENDIF
  1260. IF BESCNO == HiModel_Cool_33A_Main
  1261. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1262. $include (HiModel_Cool_33A.inc) ; Select HiModel Cool 33A pinout
  1263. ENDIF
  1264. IF BESCNO == HiModel_Cool_33A_Tail
  1265. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1266. $include (HiModel_Cool_33A.inc) ; Select HiModel Cool 33A pinout
  1267. ENDIF
  1268. IF BESCNO == HiModel_Cool_33A_Multi
  1269. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1270. $include (HiModel_Cool_33A.inc) ; Select HiModel Cool 33A pinout
  1271. ENDIF
  1272. IF BESCNO == HiModel_Cool_41A_Main
  1273. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1274. $include (HiModel_Cool_41A.inc) ; Select HiModel Cool 41A pinout
  1275. ENDIF
  1276. IF BESCNO == HiModel_Cool_41A_Tail
  1277. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1278. $include (HiModel_Cool_41A.inc) ; Select HiModel Cool 41A pinout
  1279. ENDIF
  1280. IF BESCNO == HiModel_Cool_41A_Multi
  1281. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1282. $include (HiModel_Cool_41A.inc) ; Select HiModel Cool 41A pinout
  1283. ENDIF
  1284. IF BESCNO == RCTimer_6A_Main
  1285. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1286. $include (RCTimer_6A.inc) ; Select RC Timer 6A pinout
  1287. ENDIF
  1288. IF BESCNO == RCTimer_6A_Tail
  1289. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1290. $include (RCTimer_6A.inc) ; Select RC Timer 6A pinout
  1291. ENDIF
  1292. IF BESCNO == RCTimer_6A_Multi
  1293. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1294. $include (RCTimer_6A.inc) ; Select RC Timer 6A pinout
  1295. ENDIF
  1296. IF BESCNO == Align_RCE_BL15X_Main
  1297. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1298. $include (Align_RCE_BL15X.inc) ; Select Align RCE-BL15X pinout
  1299. ENDIF
  1300. IF BESCNO == Align_RCE_BL15X_Tail
  1301. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1302. $include (Align_RCE_BL15X.inc) ; Select Align RCE-BL15X pinout
  1303. ENDIF
  1304. IF BESCNO == Align_RCE_BL15X_Multi
  1305. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1306. $include (Align_RCE_BL15X.inc) ; Select Align RCE-BL15X pinout
  1307. ENDIF
  1308. IF BESCNO == Align_RCE_BL15P_Main
  1309. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1310. $include (Align_RCE_BL15P.inc) ; Select Align RCE-BL15P pinout
  1311. ENDIF
  1312. IF BESCNO == Align_RCE_BL15P_Tail
  1313. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1314. $include (Align_RCE_BL15P.inc) ; Select Align RCE-BL15P pinout
  1315. ENDIF
  1316. IF BESCNO == Align_RCE_BL15P_Multi
  1317. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1318. $include (Align_RCE_BL15P.inc) ; Select Align RCE-BL15P pinout
  1319. ENDIF
  1320. IF BESCNO == Align_RCE_BL35X_Main
  1321. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1322. $include (Align_RCE_BL35X.inc) ; Select Align RCE-BL35X pinout
  1323. ENDIF
  1324. IF BESCNO == Align_RCE_BL35X_Tail
  1325. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1326. $include (Align_RCE_BL35X.inc) ; Select Align RCE-BL35X pinout
  1327. ENDIF
  1328. IF BESCNO == Align_RCE_BL35X_Multi
  1329. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1330. $include (Align_RCE_BL35X.inc) ; Select Align RCE-BL35X pinout
  1331. ENDIF
  1332. IF BESCNO == Align_RCE_BL35P_Main
  1333. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1334. $include (Align_RCE_BL35P.inc) ; Select Align RCE-BL35P pinout
  1335. ENDIF
  1336. IF BESCNO == Align_RCE_BL35P_Tail
  1337. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1338. $include (Align_RCE_BL35P.inc) ; Select Align RCE-BL35P pinout
  1339. ENDIF
  1340. IF BESCNO == Align_RCE_BL35P_Multi
  1341. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1342. $include (Align_RCE_BL35P.inc) ; Select Align RCE-BL35P pinout
  1343. ENDIF
  1344. IF BESCNO == Gaui_GE_183_18A_Main
  1345. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1346. $include (Gaui_GE_183_18A.inc) ; Select Gaui GE-183 18A pinout
  1347. ENDIF
  1348. IF BESCNO == Gaui_GE_183_18A_Tail
  1349. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1350. $include (Gaui_GE_183_18A.inc) ; Select Gaui GE-183 18A pinout
  1351. ENDIF
  1352. IF BESCNO == Gaui_GE_183_18A_Multi
  1353. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1354. $include (Gaui_GE_183_18A.inc) ; Select Gaui GE-183 18A pinout
  1355. ENDIF
  1356. IF BESCNO == H_King_10A_Main
  1357. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1358. $include (H_King_10A.inc) ; Select H-King 10A pinout
  1359. ENDIF
  1360. IF BESCNO == H_King_10A_Tail
  1361. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1362. $include (H_King_10A.inc) ; Select H-King 10A pinout
  1363. ENDIF
  1364. IF BESCNO == H_King_10A_Multi
  1365. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1366. $include (H_King_10A.inc) ; Select H-King 10A pinout
  1367. ENDIF
  1368. IF BESCNO == H_King_20A_Main
  1369. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1370. $include (H_King_20A.inc) ; Select H-King 20A pinout
  1371. ENDIF
  1372. IF BESCNO == H_King_20A_Tail
  1373. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1374. $include (H_King_20A.inc) ; Select H-King 20A pinout
  1375. ENDIF
  1376. IF BESCNO == H_King_20A_Multi
  1377. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1378. $include (H_King_20A.inc) ; Select H-King 20A pinout
  1379. ENDIF
  1380. IF BESCNO == H_King_35A_Main
  1381. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1382. $include (H_King_35A.inc) ; Select H-King 35A pinout
  1383. ENDIF
  1384. IF BESCNO == H_King_35A_Tail
  1385. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1386. $include (H_King_35A.inc) ; Select H-King 35A pinout
  1387. ENDIF
  1388. IF BESCNO == H_King_35A_Multi
  1389. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1390. $include (H_King_35A.inc) ; Select H-King 35A pinout
  1391. ENDIF
  1392. IF BESCNO == H_King_50A_Main
  1393. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1394. $include (H_King_50A.inc) ; Select H-King 50A pinout
  1395. ENDIF
  1396. IF BESCNO == H_King_50A_Tail
  1397. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1398. $include (H_King_50A.inc) ; Select H-King 50A pinout
  1399. ENDIF
  1400. IF BESCNO == H_King_50A_Multi
  1401. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1402. $include (H_King_50A.inc) ; Select H-King 50A pinout
  1403. ENDIF
  1404. IF BESCNO == Polaris_Thunder_12A_Main
  1405. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1406. $include (Polaris_Thunder_12A.inc) ; Select Polaris Thunder 12A pinout
  1407. ENDIF
  1408. IF BESCNO == Polaris_Thunder_12A_Tail
  1409. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1410. $include (Polaris_Thunder_12A.inc) ; Select Polaris Thunder 12A pinout
  1411. ENDIF
  1412. IF BESCNO == Polaris_Thunder_12A_Multi
  1413. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1414. $include (Polaris_Thunder_12A.inc) ; Select Polaris Thunder 12A pinout
  1415. ENDIF
  1416. IF BESCNO == Polaris_Thunder_20A_Main
  1417. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1418. $include (Polaris_Thunder_20A.inc) ; Select Polaris Thunder 20A pinout
  1419. ENDIF
  1420. IF BESCNO == Polaris_Thunder_20A_Tail
  1421. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1422. $include (Polaris_Thunder_20A.inc) ; Select Polaris Thunder 20A pinout
  1423. ENDIF
  1424. IF BESCNO == Polaris_Thunder_20A_Multi
  1425. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1426. $include (Polaris_Thunder_20A.inc) ; Select Polaris Thunder 20A pinout
  1427. ENDIF
  1428. IF BESCNO == Polaris_Thunder_30A_Main
  1429. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1430. $include (Polaris_Thunder_30A.inc) ; Select Polaris Thunder 30A pinout
  1431. ENDIF
  1432. IF BESCNO == Polaris_Thunder_30A_Tail
  1433. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1434. $include (Polaris_Thunder_30A.inc) ; Select Polaris Thunder 30A pinout
  1435. ENDIF
  1436. IF BESCNO == Polaris_Thunder_30A_Multi
  1437. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1438. $include (Polaris_Thunder_30A.inc) ; Select Polaris Thunder 30A pinout
  1439. ENDIF
  1440. IF BESCNO == Polaris_Thunder_40A_Main
  1441. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1442. $include (Polaris_Thunder_40A.inc) ; Select Polaris Thunder 40A pinout
  1443. ENDIF
  1444. IF BESCNO == Polaris_Thunder_40A_Tail
  1445. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1446. $include (Polaris_Thunder_40A.inc) ; Select Polaris Thunder 40A pinout
  1447. ENDIF
  1448. IF BESCNO == Polaris_Thunder_40A_Multi
  1449. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1450. $include (Polaris_Thunder_40A.inc) ; Select Polaris Thunder 40A pinout
  1451. ENDIF
  1452. IF BESCNO == Polaris_Thunder_60A_Main
  1453. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1454. $include (Polaris_Thunder_60A.inc) ; Select Polaris Thunder 60A pinout
  1455. ENDIF
  1456. IF BESCNO == Polaris_Thunder_60A_Tail
  1457. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1458. $include (Polaris_Thunder_60A.inc) ; Select Polaris Thunder 60A pinout
  1459. ENDIF
  1460. IF BESCNO == Polaris_Thunder_60A_Multi
  1461. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1462. $include (Polaris_Thunder_60A.inc) ; Select Polaris Thunder 60A pinout
  1463. ENDIF
  1464. IF BESCNO == Polaris_Thunder_80A_Main
  1465. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1466. $include (Polaris_Thunder_80A.inc) ; Select Polaris Thunder 80A pinout
  1467. ENDIF
  1468. IF BESCNO == Polaris_Thunder_80A_Tail
  1469. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1470. $include (Polaris_Thunder_80A.inc) ; Select Polaris Thunder 80A pinout
  1471. ENDIF
  1472. IF BESCNO == Polaris_Thunder_80A_Multi
  1473. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1474. $include (Polaris_Thunder_80A.inc) ; Select Polaris Thunder 80A pinout
  1475. ENDIF
  1476. IF BESCNO == Polaris_Thunder_100A_Main
  1477. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1478. $include (Polaris_Thunder_100A.inc); Select Polaris Thunder 100A pinout
  1479. ENDIF
  1480. IF BESCNO == Polaris_Thunder_100A_Tail
  1481. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1482. $include (Polaris_Thunder_100A.inc); Select Polaris Thunder 100A pinout
  1483. ENDIF
  1484. IF BESCNO == Polaris_Thunder_100A_Multi
  1485. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1486. $include (Polaris_Thunder_100A.inc); Select Polaris Thunder 100A pinout
  1487. ENDIF
  1488. IF BESCNO == Platinum_Pro_30A_Main
  1489. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1490. $include (Platinum_Pro_30A.inc) ; Select Platinum Pro 30A pinout
  1491. ENDIF
  1492. IF BESCNO == Platinum_Pro_30A_Tail
  1493. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1494. $include (Platinum_Pro_30A.inc) ; Select Platinum Pro 30A pinout
  1495. ENDIF
  1496. IF BESCNO == Platinum_Pro_30A_Multi
  1497. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1498. $include (Platinum_Pro_30A.inc) ; Select Platinum Pro 30A pinout
  1499. ENDIF
  1500. IF BESCNO == Platinum_Pro_150A_Main
  1501. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1502. $include (Platinum_Pro_150A.inc) ; Select Platinum Pro 150A pinout
  1503. ENDIF
  1504. IF BESCNO == Platinum_Pro_150A_Tail
  1505. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1506. $include (Platinum_Pro_150A.inc) ; Select Platinum Pro 150A pinout
  1507. ENDIF
  1508. IF BESCNO == Platinum_Pro_150A_Multi
  1509. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1510. $include (Platinum_Pro_150A.inc) ; Select Platinum Pro 150A pinout
  1511. ENDIF
  1512. IF BESCNO == Platinum_50Av3_Main
  1513. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1514. $include (Platinum_50Av3.inc) ; Select Platinum 50A v3 pinout
  1515. ENDIF
  1516. IF BESCNO == Platinum_50Av3_Tail
  1517. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1518. $include (Platinum_50Av3.inc) ; Select Platinum 50A v3 pinout
  1519. ENDIF
  1520. IF BESCNO == Platinum_50Av3_Multi
  1521. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1522. $include (Platinum_50Av3.inc) ; Select Platinum 50A v3 pinout
  1523. ENDIF
  1524. IF BESCNO == EAZY_3Av2_Main
  1525. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1526. $include (EAZY_3Av2.inc) ; Select Eazy 3A v2 pinout
  1527. ENDIF
  1528. IF BESCNO == EAZY_3Av2_Tail
  1529. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1530. $include (EAZY_3Av2.inc) ; Select Eazy 3A v2 pinout
  1531. ENDIF
  1532. IF BESCNO == EAZY_3Av2_Multi
  1533. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1534. $include (EAZY_3Av2.inc) ; Select Eazy 3A v2 pinout
  1535. ENDIF
  1536. IF BESCNO == Tarot_30A_Main
  1537. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1538. $include (Tarot_30A.inc) ; Select Tarot 30A pinout
  1539. ENDIF
  1540. IF BESCNO == Tarot_30A_Tail
  1541. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1542. $include (Tarot_30A.inc) ; Select Tarot 30A pinout
  1543. ENDIF
  1544. IF BESCNO == Tarot_30A_Multi
  1545. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1546. $include (Tarot_30A.inc) ; Select Tarot 30A pinout
  1547. ENDIF
  1548. IF BESCNO == SkyIII_30A_Main
  1549. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1550. $include (SkyIII_30A.inc) ; Select SkyIII 30A pinout
  1551. ENDIF
  1552. IF BESCNO == SkyIII_30A_Tail
  1553. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1554. $include (SkyIII_30A.inc) ; Select SkyIII 30A pinout
  1555. ENDIF
  1556. IF BESCNO == SkyIII_30A_Multi
  1557. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1558. $include (SkyIII_30A.inc) ; Select SkyIII 30A pinout
  1559. ENDIF
  1560. IF BESCNO == EMAX_20A_Main
  1561. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1562. $include (EMAX_20A.inc) ; Select EMAX 20A pinout
  1563. ENDIF
  1564. IF BESCNO == EMAX_20A_Tail
  1565. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1566. $include (EMAX_20A.inc) ; Select EMAX 20A pinout
  1567. ENDIF
  1568. IF BESCNO == EMAX_20A_Multi
  1569. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1570. $include (EMAX_20A.inc) ; Select EMAX 20A pinout
  1571. ENDIF
  1572. IF BESCNO == EMAX_40A_Main
  1573. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1574. $include (EMAX_40A.inc) ; Select EMAX 40A pinout
  1575. ENDIF
  1576. IF BESCNO == EMAX_40A_Tail
  1577. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1578. $include (EMAX_40A.inc) ; Select EMAX 40A pinout
  1579. ENDIF
  1580. IF BESCNO == EMAX_40A_Multi
  1581. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1582. $include (EMAX_40A.inc) ; Select EMAX 40A pinout
  1583. ENDIF
  1584. IF BESCNO == EMAX_Nano_20A_Main
  1585. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1586. $include (EMAX_Nano_20A.inc) ; Select EMAX Nano 20A pinout
  1587. ENDIF
  1588. IF BESCNO == EMAX_Nano_20A_Tail
  1589. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1590. $include (EMAX_Nano_20A.inc) ; Select EMAX Nano 20A pinout
  1591. ENDIF
  1592. IF BESCNO == EMAX_Nano_20A_Multi
  1593. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1594. $include (EMAX_Nano_20A.inc) ; Select EMAX Nano 20A pinout
  1595. ENDIF
  1596. IF BESCNO == EMAX_Lightning_20A_Main
  1597. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1598. $include (EMAX_Lightning_20A.inc) ; Select EMAX Lightning 20A pinout
  1599. ENDIF
  1600. IF BESCNO == EMAX_Lightning_20A_Tail
  1601. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1602. $include (EMAX_Lightning_20A.inc) ; Select EMAX Lightning 20A pinout
  1603. ENDIF
  1604. IF BESCNO == EMAX_Lightning_20A_Multi
  1605. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1606. $include (EMAX_Lightning_20A.inc) ; Select EMAX Lightning 20A pinout
  1607. ENDIF
  1608. IF BESCNO == XRotor_10A_Main
  1609. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1610. $include (XRotor_10A.inc) ; Select XRotor 10A pinout
  1611. ENDIF
  1612. IF BESCNO == XRotor_10A_Tail
  1613. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1614. $include (XRotor_10A.inc) ; Select XRotor 10A pinout
  1615. ENDIF
  1616. IF BESCNO == XRotor_10A_Multi
  1617. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1618. $include (XRotor_10A.inc) ; Select XRotor 10A pinout
  1619. ENDIF
  1620. IF BESCNO == XRotor_20A_Main
  1621. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1622. $include (XRotor_20A.inc) ; Select XRotor 20A pinout
  1623. ENDIF
  1624. IF BESCNO == XRotor_20A_Tail
  1625. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1626. $include (XRotor_20A.inc) ; Select XRotor 20A pinout
  1627. ENDIF
  1628. IF BESCNO == XRotor_20A_Multi
  1629. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1630. $include (XRotor_20A.inc) ; Select XRotor 20A pinout
  1631. ENDIF
  1632. IF BESCNO == XRotor_40A_Main
  1633. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1634. $include (XRotor_40A.inc) ; Select XRotor 40A pinout
  1635. ENDIF
  1636. IF BESCNO == XRotor_40A_Tail
  1637. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1638. $include (XRotor_40A.inc) ; Select XRotor 40A pinout
  1639. ENDIF
  1640. IF BESCNO == XRotor_40A_Multi
  1641. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1642. $include (XRotor_40A.inc) ; Select XRotor 40A pinout
  1643. ENDIF
  1644. IF BESCNO == MDRX62H_Main
  1645. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1646. $include (MDRX62H.inc) ; Select MDRX62H pinout
  1647. ENDIF
  1648. IF BESCNO == MDRX62H_Tail
  1649. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1650. $include (MDRX62H.inc) ; Select MDRX62H pinout
  1651. ENDIF
  1652. IF BESCNO == MDRX62H_Multi
  1653. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1654. $include (MDRX62H.inc) ; Select MDRX62H pinout
  1655. ENDIF
  1656. IF BESCNO == RotorGeeks_20A_Main
  1657. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1658. $include (RotorGeeks_20A.inc) ; Select RotorGeeks 20A pinout
  1659. ENDIF
  1660. IF BESCNO == RotorGeeks_20A_Tail
  1661. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1662. $include (RotorGeeks_20A.inc) ; Select RotorGeeks 20A pinout
  1663. ENDIF
  1664. IF BESCNO == RotorGeeks_20A_Multi
  1665. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1666. $include (RotorGeeks_20A.inc) ; Select RotorGeeks 20A pinout
  1667. ENDIF
  1668. IF BESCNO == RotorGeeks_20A_Plus_Main
  1669. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1670. $include (RotorGeeks_20A_Plus.inc) ; Select RotorGeeks 20A Plus pinout
  1671. ENDIF
  1672. IF BESCNO == RotorGeeks_20A_Plus_Tail
  1673. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1674. $include (RotorGeeks_20A_Plus.inc) ; Select RotorGeeks 20A Plus pinout
  1675. ENDIF
  1676. IF BESCNO == RotorGeeks_20A_Plus_Multi
  1677. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1678. $include (RotorGeeks_20A_Plus.inc) ; Select RotorGeeks 20A Plus pinout
  1679. ENDIF
  1680. IF BESCNO == Flycolor_Fairy_6A_Main
  1681. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1682. $include (Flycolor_Fairy_6A.inc) ; Select Flycolor Fairy 6A pinout
  1683. ENDIF
  1684. IF BESCNO == Flycolor_Fairy_6A_Tail
  1685. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1686. $include (Flycolor_Fairy_6A.inc) ; Select Flycolor Fairy 6A pinout
  1687. ENDIF
  1688. IF BESCNO == Flycolor_Fairy_6A_Multi
  1689. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1690. $include (Flycolor_Fairy_6A.inc) ; Select Flycolor Fairy 6A pinout
  1691. ENDIF
  1692. IF BESCNO == Flycolor_Fairy_30A_Main
  1693. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1694. $include (Flycolor_Fairy_30A.inc) ; Select Flycolor Fairy 30A pinout
  1695. ENDIF
  1696. IF BESCNO == Flycolor_Fairy_30A_Tail
  1697. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1698. $include (Flycolor_Fairy_30A.inc) ; Select Flycolor Fairy 30A pinout
  1699. ENDIF
  1700. IF BESCNO == Flycolor_Fairy_30A_Multi
  1701. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1702. $include (Flycolor_Fairy_30A.inc) ; Select Flycolor Fairy 30A pinout
  1703. ENDIF
  1704. IF BESCNO == Flycolor_Fairy_V2_30A_Main
  1705. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1706. $include (Flycolor_Fairy_V2_30A.inc) ; Select Flycolor Fairy V2 30A pinout
  1707. ENDIF
  1708. IF BESCNO == Flycolor_Fairy_V2_30A_Tail
  1709. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1710. $include (Flycolor_Fairy_V2_30A.inc) ; Select Flycolor Fairy V2 30A pinout
  1711. ENDIF
  1712. IF BESCNO == Flycolor_Fairy_V2_30A_Multi
  1713. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1714. $include (Flycolor_Fairy_V2_30A.inc) ; Select Flycolor Fairy V2 30A pinout
  1715. ENDIF
  1716. IF BESCNO == Flycolor_Raptor_20A_Main
  1717. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1718. $include (Flycolor_Raptor_20A.inc) ; Select Flycolor Raptor 20A pinout
  1719. ENDIF
  1720. IF BESCNO == Flycolor_Raptor_20A_Tail
  1721. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1722. $include (Flycolor_Raptor_20A.inc) ; Select Flycolor Raptor 20A pinout
  1723. ENDIF
  1724. IF BESCNO == Flycolor_Raptor_20A_Multi
  1725. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1726. $include (Flycolor_Raptor_20A.inc) ; Select Flycolor Raptor 20A pinout
  1727. ENDIF
  1728. IF BESCNO == Flycolor_Raptor_390_20A_Main
  1729. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1730. $include (Flycolor_Raptor_390_20A.inc) ; Select Flycolor Raptor 390 20A pinout
  1731. ENDIF
  1732. IF BESCNO == Flycolor_Raptor_390_20A_Tail
  1733. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1734. $include (Flycolor_Raptor_390_20A.inc) ; Select Flycolor Raptor 390 20A pinout
  1735. ENDIF
  1736. IF BESCNO == Flycolor_Raptor_390_20A_Multi
  1737. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1738. $include (Flycolor_Raptor_390_20A.inc) ; Select Flycolor Raptor 390 20A pinout
  1739. ENDIF
  1740. IF BESCNO == FVT_Littlebee_12A_Main
  1741. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1742. $include (FVT_Littlebee_12A.inc) ; Select Favourite Littlebee 12A pinout
  1743. ENDIF
  1744. IF BESCNO == FVT_Littlebee_12A_Tail
  1745. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1746. $include (FVT_Littlebee_12A.inc) ; Select Favourite Littlebee 12A pinout
  1747. ENDIF
  1748. IF BESCNO == FVT_Littlebee_12A_Multi
  1749. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1750. $include (FVT_Littlebee_12A.inc) ; Select Favourite Littlebee 12A pinout
  1751. ENDIF
  1752. IF BESCNO == FVT_Littlebee_20A_Main
  1753. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1754. $include (FVT_Littlebee_20A.inc) ; Select Favourite Littlebee 20A pinout
  1755. ENDIF
  1756. IF BESCNO == FVT_Littlebee_20A_Tail
  1757. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1758. $include (FVT_Littlebee_20A.inc) ; Select Favourite Littlebee 20A pinout
  1759. ENDIF
  1760. IF BESCNO == FVT_Littlebee_20A_Multi
  1761. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1762. $include (FVT_Littlebee_20A.inc) ; Select Favourite Littlebee 20A pinout
  1763. ENDIF
  1764. IF BESCNO == FVT_Littlebee_20A_Pro_Main
  1765. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1766. $include (FVT_Littlebee_20A_Pro.inc) ; Select Favourite Littlebee 20A Pro pinout
  1767. ENDIF
  1768. IF BESCNO == FVT_Littlebee_20A_Pro_Tail
  1769. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1770. $include (FVT_Littlebee_20A_Pro.inc) ; Select Favourite Littlebee 20A Pro pinout
  1771. ENDIF
  1772. IF BESCNO == FVT_Littlebee_20A_Pro_Multi
  1773. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1774. $include (FVT_Littlebee_20A_Pro.inc) ; Select Favourite Littlebee 20A Pro pinout
  1775. ENDIF
  1776. IF BESCNO == FVT_Littlebee_30A_Main
  1777. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1778. $include (FVT_Littlebee_30A.inc) ; Select Favourite Littlebee 30A pinout
  1779. ENDIF
  1780. IF BESCNO == FVT_Littlebee_30A_Tail
  1781. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1782. $include (FVT_Littlebee_30A.inc) ; Select Favourite Littlebee 30A pinout
  1783. ENDIF
  1784. IF BESCNO == FVT_Littlebee_30A_Multi
  1785. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1786. $include (FVT_Littlebee_30A.inc) ; Select Favourite Littlebee 30A pinout
  1787. ENDIF
  1788. IF BESCNO == Graupner_Ultra_20A_Main
  1789. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1790. $include (Graupner_Ultra_20A.inc) ; Select Graupner Ultra 20A pinout
  1791. ENDIF
  1792. IF BESCNO == Graupner_Ultra_20A_Tail
  1793. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1794. $include (Graupner_Ultra_20A.inc) ; Select Graupner Ultra 20A pinout
  1795. ENDIF
  1796. IF BESCNO == Graupner_Ultra_20A_Multi
  1797. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1798. $include (Graupner_Ultra_20A.inc) ; Select Graupner Ultra 20A pinout
  1799. ENDIF
  1800. IF BESCNO == F85_3A_Main
  1801. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1802. $include (F85_3A.inc) ; Select F85 3A pinout
  1803. ENDIF
  1804. IF BESCNO == F85_3A_Tail
  1805. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1806. $include (F85_3A.inc) ; Select F85 3A pinout
  1807. ENDIF
  1808. IF BESCNO == F85_3A_Multi
  1809. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1810. $include (F85_3A.inc) ; Select F85 3A pinout
  1811. ENDIF
  1812. IF BESCNO == ZTW_Spider_Pro_20A_Main
  1813. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1814. $include (ZTW_Spider_Pro_20A.inc) ; Select ZTW Spider Pro 20A pinout
  1815. ENDIF
  1816. IF BESCNO == ZTW_Spider_Pro_20A_Tail
  1817. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1818. $include (ZTW_Spider_Pro_20A.inc) ; Select ZTW Spider Pro 20A pinout
  1819. ENDIF
  1820. IF BESCNO == ZTW_Spider_Pro_20A_Multi
  1821. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1822. $include (ZTW_Spider_Pro_20A.inc) ; Select ZTW Spider Pro 20A pinout
  1823. ENDIF
  1824. IF BESCNO == ZTW_Spider_Pro_20A_Premium_Main
  1825. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1826. $include (ZTW_Spider_Pro_20A_Premium.inc) ; Select ZTW Spider Pro 20A Premium pinout
  1827. ENDIF
  1828. IF BESCNO == ZTW_Spider_Pro_20A_Premium_Tail
  1829. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1830. $include (ZTW_Spider_Pro_20A_Premium.inc) ; Select ZTW Spider Pro 20A Premium pinout
  1831. ENDIF
  1832. IF BESCNO == ZTW_Spider_Pro_20A_Premium_Multi
  1833. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1834. $include (ZTW_Spider_Pro_20A_Premium.inc) ; Select ZTW Spider Pro 20A Premium pinout
  1835. ENDIF
  1836. IF BESCNO == ZTW_Spider_Pro_20A_HV_Main
  1837. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1838. $include (ZTW_Spider_Pro_20A_HV.inc) ; Select ZTW Spider Pro 20A HV pinout
  1839. ENDIF
  1840. IF BESCNO == ZTW_Spider_Pro_20A_HV_Tail
  1841. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1842. $include (ZTW_Spider_Pro_20A_HV.inc) ; Select ZTW Spider Pro 20A HV pinout
  1843. ENDIF
  1844. IF BESCNO == ZTW_Spider_Pro_20A_HV_Multi
  1845. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1846. $include (ZTW_Spider_Pro_20A_HV.inc) ; Select ZTW Spider Pro 20A HV pinout
  1847. ENDIF
  1848. IF BESCNO == ZTW_Spider_Pro_30A_HV_Main
  1849. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1850. $include (ZTW_Spider_Pro_30A_HV.inc) ; Select ZTW Spider Pro 30A HV pinout
  1851. ENDIF
  1852. IF BESCNO == ZTW_Spider_Pro_30A_HV_Tail
  1853. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1854. $include (ZTW_Spider_Pro_30A_HV.inc) ; Select ZTW Spider Pro 30A HV pinout
  1855. ENDIF
  1856. IF BESCNO == ZTW_Spider_Pro_30A_HV_Multi
  1857. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1858. $include (ZTW_Spider_Pro_30A_HV.inc) ; Select ZTW Spider Pro 30A HV pinout
  1859. ENDIF
  1860. IF BESCNO == DYS_XM20A_Main
  1861. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1862. $include (DYS_XM20A.inc) ; Select DYS XM20A pinout
  1863. ENDIF
  1864. IF BESCNO == DYS_XM20A_Tail
  1865. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1866. $include (DYS_XM20A.inc) ; Select DYS XM20A pinout
  1867. ENDIF
  1868. IF BESCNO == DYS_XM20A_Multi
  1869. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1870. $include (DYS_XM20A.inc) ; Select DYS XM20A pinout
  1871. ENDIF
  1872. IF BESCNO == Oversky_MR_20A_Main
  1873. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1874. $include (Oversky_MR_20A.inc) ; Select Oversky MR-20A pinout
  1875. ENDIF
  1876. IF BESCNO == Oversky_MR_20A_Tail
  1877. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1878. $include (Oversky_MR_20A.inc) ; Select Oversky MR-20A pinout
  1879. ENDIF
  1880. IF BESCNO == Oversky_MR_20A_Multi
  1881. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1882. $include (Oversky_MR_20A.inc) ; Select Oversky MR-20A pinout
  1883. ENDIF
  1884. IF BESCNO == Oversky_MR_20A_Pro_Main
  1885. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1886. $include (Oversky_MR_20A_Pro.inc) ; Select Oversky MR-20A Pro pinout
  1887. ENDIF
  1888. IF BESCNO == Oversky_MR_20A_Pro_Tail
  1889. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1890. $include (Oversky_MR_20A_Pro.inc) ; Select Oversky MR-20A Pro pinout
  1891. ENDIF
  1892. IF BESCNO == Oversky_MR_20A_Pro_Multi
  1893. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1894. $include (Oversky_MR_20A_Pro.inc) ; Select Oversky MR-20A Pro pinout
  1895. ENDIF
  1896. IF BESCNO == TBS_Cube_12A_Main
  1897. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1898. $include (TBS_Cube_12A.inc) ; Select TBS Cube 12A pinout
  1899. ENDIF
  1900. IF BESCNO == TBS_Cube_12A_Tail
  1901. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1902. $include (TBS_Cube_12A.inc) ; Select TBS Cube 12A pinout
  1903. ENDIF
  1904. IF BESCNO == TBS_Cube_12A_Multi
  1905. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1906. $include (TBS_Cube_12A.inc) ; Select TBS Cube 12A pinout
  1907. ENDIF
  1908. IF BESCNO == DALRC_XR20A_Main
  1909. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1910. $include (DALRC_XR20A.inc) ; Select DALRC 20A pinout
  1911. ENDIF
  1912. IF BESCNO == DALRC_XR20A_Tail
  1913. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1914. $include (DALRC_XR20A.inc) ; Select DALRC 20A pinout
  1915. ENDIF
  1916. IF BESCNO == DALRC_XR20A_Multi
  1917. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1918. $include (DALRC_XR20A.inc) ; Select DALRC 20A pinout
  1919. ENDIF
  1920. IF BESCNO == AIKON_Boltlite_30A_Main
  1921. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1922. $include (AIKON_Boltlite_30A.inc) ; Select AIKON_Boltlite 30A pinout
  1923. ENDIF
  1924. IF BESCNO == AIKON_Boltlite_30A_Tail
  1925. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1926. $include (AIKON_Boltlite_30A.inc) ; Select AIKON_Boltlite 30A pinout
  1927. ENDIF
  1928. IF BESCNO == AIKON_Boltlite_30A_Multi
  1929. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1930. $include (AIKON_Boltlite_30A.inc) ; Select AIKON_Boltlite 30A pinout
  1931. ENDIF
  1932. IF BESCNO == Align_MR25_15A_Main
  1933. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1934. $include (Align_MR25_15A.inc) ; Select Align MR25 15A pinout
  1935. ENDIF
  1936. IF BESCNO == Align_MR25_15A_Tail
  1937. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1938. $include (Align_MR25_15A.inc) ; Select Align MR25 15A pinout
  1939. ENDIF
  1940. IF BESCNO == Align_MR25_15A_Multi
  1941. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1942. $include (Align_MR25_15A.inc) ; Select Align MR25 15A pinout
  1943. ENDIF
  1944. IF BESCNO == Servoking_Monster_30A_Main
  1945. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1946. $include (Servoking_Monster_30A.inc) ; Select Servoking Monster 30A pinout
  1947. ENDIF
  1948. IF BESCNO == Servoking_Monster_30A_Tail
  1949. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1950. $include (Servoking_Monster_30A.inc) ; Select Servoking Monster 30A pinout
  1951. ENDIF
  1952. IF BESCNO == Servoking_Monster_30A_Multi
  1953. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1954. $include (Servoking_Monster_30A.inc) ; Select Servoking Monster 30A pinout
  1955. ENDIF
  1956. IF BESCNO == Servoking_Monster_30A_Pro_Main
  1957. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1958. $include (Servoking_Monster_30A_Pro.inc) ; Select Servoking Monster 30A Pro pinout
  1959. ENDIF
  1960. IF BESCNO == Servoking_Monster_30A_Pro_Tail
  1961. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1962. $include (Servoking_Monster_30A_Pro.inc) ; Select Servoking Monster 30A Pro pinout
  1963. ENDIF
  1964. IF BESCNO == Servoking_Monster_30A_Pro_Multi
  1965. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1966. $include (Servoking_Monster_30A_Pro.inc) ; Select Servoking Monster 30A Pro pinout
  1967. ENDIF
  1968. IF BESCNO == Servoking_Monster_70A_Pro_Main
  1969. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1970. $include (Servoking_Monster_70A_Pro.inc) ; Select Servoking Monster 70A Pro pinout
  1971. ENDIF
  1972. IF BESCNO == Servoking_Monster_70A_Pro_Tail
  1973. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1974. $include (Servoking_Monster_70A_Pro.inc) ; Select Servoking Monster 70A Pro pinout
  1975. ENDIF
  1976. IF BESCNO == Servoking_Monster_70A_Pro_Multi
  1977. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1978. $include (Servoking_Monster_70A_Pro.inc) ; Select Servoking Monster 70A Pro pinout
  1979. ENDIF
  1980. IF BESCNO == Servoking_Monster_80A_Main
  1981. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1982. $include (Servoking_Monster_80A.inc) ; Select Servoking Monster 80A pinout
  1983. ENDIF
  1984. IF BESCNO == Servoking_Monster_80A_Tail
  1985. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1986. $include (Servoking_Monster_80A.inc) ; Select Servoking Monster 80A pinout
  1987. ENDIF
  1988. IF BESCNO == Servoking_Monster_80A_Multi
  1989. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  1990. $include (Servoking_Monster_80A.inc) ; Select Servoking Monster 80A pinout
  1991. ENDIF
  1992. IF BESCNO == HTIRC_Hummingbird_12A_Main
  1993. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  1994. $include (HTIRC_Hummingbird_12A.inc) ; Select HTIRC Hummingbird 12A pinout
  1995. ENDIF
  1996. IF BESCNO == HTIRC_Hummingbird_12A_Tail
  1997. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  1998. $include (HTIRC_Hummingbird_12A.inc) ; Select HTIRC Hummingbird 12A pinout
  1999. ENDIF
  2000. IF BESCNO == HTIRC_Hummingbird_12A_Multi
  2001. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  2002. $include (HTIRC_Hummingbird_12A.inc) ; Select HTIRC Hummingbird 12A pinout
  2003. ENDIF
  2004. IF BESCNO == HTIRC_Hummingbird_20A_Main
  2005. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  2006. $include (HTIRC_Hummingbird_20A.inc) ; Select HTIRC Hummingbird 20A pinout
  2007. ENDIF
  2008. IF BESCNO == HTIRC_Hummingbird_20A_Tail
  2009. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  2010. $include (HTIRC_Hummingbird_20A.inc) ; Select HTIRC Hummingbird 20A pinout
  2011. ENDIF
  2012. IF BESCNO == HTIRC_Hummingbird_20A_Multi
  2013. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  2014. $include (HTIRC_Hummingbird_20A.inc) ; Select HTIRC Hummingbird 20A pinout
  2015. ENDIF
  2016. IF BESCNO == HTIRC_Hummingbird_30A_Pro_Main
  2017. MODE EQU 0 ; Choose mode. Set to 0 for main motor
  2018. $include (HTIRC_Hummingbird_30A_Pro.inc) ; Select HTIRC Hummingbird 30A Pro pinout
  2019. ENDIF
  2020. IF BESCNO == HTIRC_Hummingbird_30A_Pro_Tail
  2021. MODE EQU 1 ; Choose mode. Set to 1 for tail motor
  2022. $include (HTIRC_Hummingbird_30A_Pro.inc) ; Select HTIRC Hummingbird 30A Pro pinout
  2023. ENDIF
  2024. IF BESCNO == HTIRC_Hummingbird_30A_Pro_Multi
  2025. MODE EQU 2 ; Choose mode. Set to 2 for multirotor
  2026. $include (HTIRC_Hummingbird_30A_Pro.inc) ; Select HTIRC Hummingbird 30A Pro pinout
  2027. ENDIF
  2028. ;**** **** **** **** ****
  2029. ; TX programming defaults
  2030. ;
  2031. ; Parameter dependencies:
  2032. ; - Governor P gain, I gain and Range is only used if one of the three governor modes is selected
  2033. ; - Governor setup target is only used if Setup governor mode is selected (or closed loop mode is on for multi)
  2034. ;
  2035. ; MAIN
  2036. 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
  2037. 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
  2038. DEFAULT_PGM_MAIN_GOVERNOR_MODE EQU 1 ; 1=Tx 2=Arm 3=Setup 4=Off
  2039. DEFAULT_PGM_MAIN_GOVERNOR_RANGE EQU 1 ; 1=High 2=Middle 3=Low
  2040. 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
  2041. DEFAULT_PGM_MAIN_COMM_TIMING EQU 3 ; 1=Low 2=MediumLow 3=Medium 4=MediumHigh 5=High
  2042. IF DAMPED_MODE_ENABLE == 1
  2043. DEFAULT_PGM_MAIN_PWM_FREQ EQU 2 ; 1=High 2=Low 3=DampedLight
  2044. ELSE
  2045. DEFAULT_PGM_MAIN_PWM_FREQ EQU 2 ; 1=High 2=Low
  2046. ENDIF
  2047. DEFAULT_PGM_MAIN_DEMAG_COMP EQU 1 ; 1=Disabled 2=Low 3=High
  2048. DEFAULT_PGM_MAIN_DIRECTION EQU 1 ; 1=Normal 2=Reversed
  2049. DEFAULT_PGM_MAIN_RCP_PWM_POL EQU 1 ; 1=Positive 2=Negative
  2050. DEFAULT_PGM_MAIN_GOV_SETUP_TARGET EQU 180 ; Target for governor in setup mode. Corresponds to 70% throttle
  2051. DEFAULT_PGM_MAIN_REARM_START EQU 0 ; 1=Enabled 0=Disabled
  2052. DEFAULT_PGM_MAIN_BEEP_STRENGTH EQU 120 ; Beep strength
  2053. DEFAULT_PGM_MAIN_BEACON_STRENGTH EQU 200 ; Beacon strength
  2054. DEFAULT_PGM_MAIN_BEACON_DELAY EQU 4 ; 1=1m 2=2m 3=5m 4=10m 5=Infinite
  2055. ; TAIL
  2056. DEFAULT_PGM_TAIL_GAIN EQU 3 ; 1=0.75 2=0.88 3=1.00 4=1.12 5=1.25
  2057. DEFAULT_PGM_TAIL_IDLE_SPEED EQU 4 ; 1=Low 2=MediumLow 3=Medium 4=MediumHigh 5=High
  2058. DEFAULT_PGM_TAIL_COMM_TIMING EQU 3 ; 1=Low 2=MediumLow 3=Medium 4=MediumHigh 5=High
  2059. IF DAMPED_MODE_ENABLE == 1
  2060. DEFAULT_PGM_TAIL_PWM_FREQ EQU 3 ; 1=High 2=Low 3=DampedLight
  2061. ELSE
  2062. DEFAULT_PGM_TAIL_PWM_FREQ EQU 1 ; 1=High 2=Low
  2063. ENDIF
  2064. DEFAULT_PGM_TAIL_DEMAG_COMP EQU 1 ; 1=Disabled 2=Low 3=High
  2065. DEFAULT_PGM_TAIL_DIRECTION EQU 1 ; 1=Normal 2=Reversed 3=Bidirectional
  2066. DEFAULT_PGM_TAIL_RCP_PWM_POL EQU 1 ; 1=Positive 2=Negative
  2067. DEFAULT_PGM_TAIL_BEEP_STRENGTH EQU 250 ; Beep strength
  2068. DEFAULT_PGM_TAIL_BEACON_STRENGTH EQU 250 ; Beacon strength
  2069. DEFAULT_PGM_TAIL_BEACON_DELAY EQU 4 ; 1=1m 2=2m 3=5m 4=10m 5=Infinite
  2070. DEFAULT_PGM_TAIL_PWM_DITHER EQU 3 ; 1=Off 2=3 3=7 4=15 5=31
  2071. ; MULTI
  2072. 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
  2073. 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
  2074. DEFAULT_PGM_MULTI_GOVERNOR_MODE EQU 4 ; 1=HiRange 2=MidRange 3=LoRange 4=Off
  2075. DEFAULT_PGM_MULTI_GAIN EQU 3 ; 1=0.75 2=0.88 3=1.00 4=1.12 5=1.25
  2076. DEFAULT_PGM_MULTI_COMM_TIMING EQU 3 ; 1=Low 2=MediumLow 3=Medium 4=MediumHigh 5=High
  2077. IF DAMPED_MODE_ENABLE == 1
  2078. DEFAULT_PGM_MULTI_PWM_FREQ EQU 3 ; 1=High 2=Low 3=DampedLight
  2079. ELSE
  2080. DEFAULT_PGM_MULTI_PWM_FREQ EQU 1 ; 1=High 2=Low
  2081. ENDIF
  2082. DEFAULT_PGM_MULTI_DEMAG_COMP EQU 2 ; 1=Disabled 2=Low 3=High
  2083. DEFAULT_PGM_MULTI_DIRECTION EQU 1 ; 1=Normal 2=Reversed 3=Bidirectional
  2084. DEFAULT_PGM_MULTI_RCP_PWM_POL EQU 1 ; 1=Positive 2=Negative
  2085. DEFAULT_PGM_MULTI_BEEP_STRENGTH EQU 40 ; Beep strength
  2086. DEFAULT_PGM_MULTI_BEACON_STRENGTH EQU 80 ; Beacon strength
  2087. DEFAULT_PGM_MULTI_BEACON_DELAY EQU 4 ; 1=1m 2=2m 3=5m 4=10m 5=Infinite
  2088. DEFAULT_PGM_MULTI_PWM_DITHER EQU 3 ; 1=Off 2=3 3=7 4=15 5=31
  2089. ; COMMON
  2090. DEFAULT_PGM_ENABLE_TX_PROGRAM EQU 1 ; 1=Enabled 0=Disabled
  2091. DEFAULT_PGM_PPM_MIN_THROTTLE EQU 37 ; 4*37+1000=1148
  2092. DEFAULT_PGM_PPM_MAX_THROTTLE EQU 208 ; 4*208+1000=1832
  2093. DEFAULT_PGM_PPM_CENTER_THROTTLE EQU 122 ; 4*122+1000=1488 (used in bidirectional mode)
  2094. DEFAULT_PGM_BEC_VOLTAGE_HIGH EQU 0 ; 0=Low 1+= High or higher
  2095. DEFAULT_PGM_ENABLE_TEMP_PROT EQU 1 ; 1=Enabled 0=Disabled
  2096. DEFAULT_PGM_ENABLE_POWER_PROT EQU 1 ; 1=Enabled 0=Disabled
  2097. DEFAULT_PGM_ENABLE_PWM_INPUT EQU 0 ; 1=Enabled 0=Disabled
  2098. DEFAULT_PGM_BRAKE_ON_STOP EQU 0 ; 1=Enabled 0=Disabled
  2099. ;**** **** **** **** ****
  2100. ; Constant definitions for main
  2101. IF MODE == 0
  2102. GOV_SPOOLRATE EQU 2 ; Number of steps for governor requested pwm per 32ms
  2103. RCP_TIMEOUT_PPM EQU 10 ; Number of timer2H overflows (about 32ms) before considering rc pulse lost
  2104. RCP_TIMEOUT EQU 64 ; Number of timer2L overflows (about 128us) before considering rc pulse lost
  2105. RCP_SKIP_RATE EQU 32 ; Number of timer2L overflows (about 128us) before reenabling rc pulse detection
  2106. RCP_MIN EQU 0 ; This is minimum RC pulse length
  2107. RCP_MAX EQU 255 ; This is maximum RC pulse length
  2108. RCP_VALIDATE EQU 2 ; Require minimum this pulse length to validate RC pulse
  2109. RCP_STOP EQU 1 ; Stop motor at or below this pulse length
  2110. RCP_STOP_LIMIT EQU 250 ; Stop motor if this many timer2H overflows (~32ms) are below stop limit
  2111. PWM_START EQU 50 ; PWM used as max power during start
  2112. COMM_TIME_MIN EQU 1 ; Minimum time (in us) for commutation wait
  2113. TEMP_CHECK_RATE EQU 8 ; Number of adc conversions for each check of temperature (the other conversions are used for voltage)
  2114. ENDIF
  2115. ; Constant definitions for tail
  2116. IF MODE == 1
  2117. GOV_SPOOLRATE EQU 1 ; Number of steps for governor requested pwm per 32ms
  2118. RCP_TIMEOUT_PPM EQU 10 ; Number of timer2H overflows (about 32ms) before considering rc pulse lost
  2119. RCP_TIMEOUT EQU 24 ; Number of timer2L overflows (about 128us) before considering rc pulse lost
  2120. RCP_SKIP_RATE EQU 6 ; Number of timer2L overflows (about 128us) before reenabling rc pulse detection
  2121. RCP_MIN EQU 0 ; This is minimum RC pulse length
  2122. RCP_MAX EQU 255 ; This is maximum RC pulse length
  2123. RCP_VALIDATE EQU 2 ; Require minimum this pulse length to validate RC pulse
  2124. RCP_STOP EQU 1 ; Stop motor at or below this pulse length
  2125. RCP_STOP_LIMIT EQU 130 ; Stop motor if this many timer2H overflows (~32ms) are below stop limit
  2126. PWM_START EQU 50 ; PWM used as max power during start
  2127. COMM_TIME_MIN EQU 1 ; Minimum time (in us) for commutation wait
  2128. TEMP_CHECK_RATE EQU 8 ; Number of adc conversions for each check of temperature (the other conversions are used for voltage)
  2129. ENDIF
  2130. ; Constant definitions for multi
  2131. IF MODE == 2
  2132. GOV_SPOOLRATE EQU 1 ; Number of steps for governor requested pwm per 32ms
  2133. RCP_TIMEOUT_PPM EQU 10 ; Number of timer2H overflows (about 32ms) before considering rc pulse lost
  2134. RCP_TIMEOUT EQU 24 ; Number of timer2L overflows (about 128us) before considering rc pulse lost
  2135. RCP_SKIP_RATE EQU 6 ; Number of timer2L overflows (about 128us) before reenabling rc pulse detection
  2136. RCP_MIN EQU 0 ; This is minimum RC pulse length
  2137. RCP_MAX EQU 255 ; This is maximum RC pulse length
  2138. RCP_VALIDATE EQU 2 ; Require minimum this pulse length to validate RC pulse
  2139. RCP_STOP EQU 1 ; Stop motor at or below this pulse length
  2140. RCP_STOP_LIMIT EQU 250 ; Stop motor if this many timer2H overflows (~32ms) are below stop limit
  2141. PWM_START EQU 50 ; PWM used as max power during start
  2142. COMM_TIME_MIN EQU 1 ; Minimum time (in us) for commutation wait
  2143. TEMP_CHECK_RATE EQU 8 ; Number of adc conversions for each check of temperature (the other conversions are used for voltage)
  2144. ENDIF
  2145. ;**** **** **** **** ****
  2146. ; Temporary register definitions
  2147. Temp1 EQU R0
  2148. Temp2 EQU R1
  2149. Temp3 EQU R2
  2150. Temp4 EQU R3
  2151. Temp5 EQU R4
  2152. Temp6 EQU R5
  2153. Temp7 EQU R6
  2154. Temp8 EQU R7
  2155. ;**** **** **** **** ****
  2156. ; Register definitions
  2157. DSEG AT 20h ; Variables segment
  2158. Bit_Access: DS 1 ; MUST BE AT THIS ADDRESS. Variable at bit accessible address (for non interrupt routines)
  2159. Bit_Access_Int: DS 1 ; Variable at bit accessible address (for interrupts)
  2160. Requested_Pwm: DS 1 ; Requested pwm (from RC pulse value)
  2161. Governor_Req_Pwm: DS 1 ; Governor requested pwm (sets governor target)
  2162. Current_Pwm: DS 1 ; Current pwm
  2163. Current_Pwm_Limited: DS 1 ; Current pwm that is limited
  2164. Current_Pwm_Lim_Dith: DS 1 ; Current pwm that is limited and dithered (applied to the motor output)
  2165. Rcp_Prev_Edge_L: DS 1 ; RC pulse previous edge timer3 timestamp (lo byte)
  2166. Rcp_Prev_Edge_H: DS 1 ; RC pulse previous edge timer3 timestamp (hi byte)
  2167. Rcp_Outside_Range_Cnt: DS 1 ; RC pulse outside range counter (incrementing)
  2168. Rcp_Timeout_Cntd: DS 1 ; RC pulse timeout counter (decrementing)
  2169. Rcp_Skip_Cntd: DS 1 ; RC pulse skip counter (decrementing)
  2170. Flags0: DS 1 ; State flags. Reset upon init_start
  2171. T3_PENDING EQU 0 ; Timer3 pending flag
  2172. RCP_MEAS_PWM_FREQ EQU 1 ; Measure RC pulse pwm frequency
  2173. PWM_ON EQU 2 ; Set in on part of pwm cycle
  2174. PWM_TIMER0_OVERFLOW EQU 3 ; Set for 48MHz MCUs when PWM timer 0 overflows
  2175. DEMAG_DETECTED EQU 4 ; Set when excessive demag time is detected
  2176. DEMAG_CUT_POWER EQU 5 ; Set when demag compensation cuts power
  2177. HIGH_RPM EQU 6 ; Set when motor rpm is high (Comm_Period4x_H less than 2)
  2178. ; EQU 7
  2179. Flags1: DS 1 ; State flags. Reset upon init_start
  2180. MOTOR_SPINNING EQU 0 ; Set when in motor is spinning
  2181. STARTUP_PHASE EQU 1 ; Set when in startup phase
  2182. INITIAL_RUN_PHASE EQU 2 ; Set when in initial run phase, before synchronized run is achieved
  2183. MOTOR_STARTED EQU 3 ; Set when motor is started
  2184. DIR_CHANGE_BRAKE EQU 4 ; Set when braking before direction change
  2185. COMP_TIMED_OUT EQU 5 ; Set when comparator reading timed out
  2186. GOV_ACTIVE EQU 6 ; Set when governor is active (enabled when speed is above minimum)
  2187. SKIP_DAMP_ON EQU 7 ; Set when turning damping fet on is skipped
  2188. Flags2: DS 1 ; State flags. NOT reset upon init_start
  2189. RCP_UPDATED EQU 0 ; New RC pulse length value available
  2190. RCP_EDGE_NO EQU 1 ; RC pulse edge no. 0=rising, 1=falling
  2191. PGM_PWMOFF_DAMPED EQU 2 ; Programmed pwm off damped mode
  2192. PGM_PWM_HIGH_FREQ EQU 3 ; Progremmed pwm high frequency
  2193. RCP_PPM EQU 4 ; RC pulse ppm type input (set also when oneshot is set)
  2194. RCP_PPM_ONESHOT125 EQU 5 ; RC pulse ppm type input is OneShot125
  2195. RCP_DIR_REV EQU 6 ; RC pulse direction in bidirectional mode
  2196. ; EQU 7
  2197. Flags3: DS 1 ; State flags. NOT reset upon init_start
  2198. RCP_PWM_FREQ_1KHZ EQU 0 ; RC pulse pwm frequency is 1kHz
  2199. RCP_PWM_FREQ_2KHZ EQU 1 ; RC pulse pwm frequency is 2kHz
  2200. RCP_PWM_FREQ_4KHZ EQU 2 ; RC pulse pwm frequency is 4kHz
  2201. RCP_PWM_FREQ_8KHZ EQU 3 ; RC pulse pwm frequency is 8kHz
  2202. RCP_PWM_FREQ_12KHZ EQU 4 ; RC pulse pwm frequency is 12kHz
  2203. PGM_DIR_REV EQU 5 ; Programmed direction. 0=normal, 1=reversed
  2204. PGM_RCP_PWM_POL EQU 6 ; Programmed RC pulse pwm polarity. 0=positive, 1=negative
  2205. FULL_THROTTLE_RANGE EQU 7 ; When set full throttle range is used (1000-2000us) and stored calibration values are ignored
  2206. ;**** **** **** **** ****
  2207. ; RAM definitions
  2208. DSEG AT 30h ; Ram data segment, direct addressing
  2209. Initial_Arm: DS 1 ; Variable that is set during the first arm sequence after power on
  2210. Power_On_Wait_Cnt_L: DS 1 ; Power on wait counter (lo byte)
  2211. Power_On_Wait_Cnt_H: DS 1 ; Power on wait counter (hi byte)
  2212. Startup_Cnt: DS 1 ; Startup phase commutations counter (incrementing)
  2213. Startup_Zc_Timeout_Cntd: DS 1 ; Startup zero cross timeout counter (decrementing)
  2214. Initial_Run_Rot_Cntd: DS 1 ; Initial run rotations counter (decrementing)
  2215. Stall_Cnt: DS 1 ; Counts start/run attempts that resulted in stall. Reset upon a proper stop
  2216. Demag_Detected_Metric: DS 1 ; Metric used to gauge demag event frequency
  2217. Demag_Pwr_Off_Thresh: DS 1 ; Metric threshold above which power is cut
  2218. Low_Rpm_Pwr_Slope: DS 1 ; Sets the slope of power increase for low rpms
  2219. Timer2_X: DS 1 ; Timer 2 extended byte
  2220. Prev_Comm_L: DS 1 ; Previous commutation timer3 timestamp (lo byte)
  2221. Prev_Comm_H: DS 1 ; Previous commutation timer3 timestamp (hi byte)
  2222. Prev_Comm_X: DS 1 ; Previous commutation timer3 timestamp (ext byte)
  2223. Prev_Prev_Comm_L: DS 1 ; Pre-previous commutation timer3 timestamp (lo byte)
  2224. Prev_Prev_Comm_H: DS 1 ; Pre-previous commutation timer3 timestamp (hi byte)
  2225. Comm_Period4x_L: DS 1 ; Timer3 counts between the last 4 commutations (lo byte)
  2226. Comm_Period4x_H: DS 1 ; Timer3 counts between the last 4 commutations (hi byte)
  2227. Comm_Phase: DS 1 ; Current commutation phase
  2228. Comparator_Read_Cnt: DS 1 ; Number of comparator reads done
  2229. Gov_Target_L: DS 1 ; Governor target (lo byte)
  2230. Gov_Target_H: DS 1 ; Governor target (hi byte)
  2231. Gov_Integral_L: DS 1 ; Governor integral error (lo byte)
  2232. Gov_Integral_H: DS 1 ; Governor integral error (hi byte)
  2233. Gov_Integral_X: DS 1 ; Governor integral error (ex byte)
  2234. Gov_Proportional_L: DS 1 ; Governor proportional error (lo byte)
  2235. Gov_Proportional_H: DS 1 ; Governor proportional error (hi byte)
  2236. Gov_Prop_Pwm: DS 1 ; Governor calculated new pwm based upon proportional error
  2237. Gov_Arm_Target: DS 1 ; Governor arm target value
  2238. Wt_Adv_Start_L: DS 1 ; Timer3 start point for commutation advance timing (lo byte)
  2239. Wt_Adv_Start_H: DS 1 ; Timer3 start point for commutation advance timing (hi byte)
  2240. Wt_Zc_Scan_Start_L: DS 1 ; Timer3 start point from commutation to zero cross scan (lo byte)
  2241. Wt_Zc_Scan_Start_H: DS 1 ; Timer3 start point from commutation to zero cross scan (hi byte)
  2242. Wt_Zc_Tout_Start_L: DS 1 ; Timer3 start point for zero cross scan timeout (lo byte)
  2243. Wt_Zc_Tout_Start_H: DS 1 ; Timer3 start point for zero cross scan timeout (hi byte)
  2244. Wt_Comm_Start_L: DS 1 ; Timer3 start point from zero cross to commutation (lo byte)
  2245. Wt_Comm_Start_H: DS 1 ; Timer3 start point from zero cross to commutation (hi byte)
  2246. Rcp_PrePrev_Edge_L: DS 1 ; RC pulse pre previous edge pca timestamp (lo byte)
  2247. Rcp_PrePrev_Edge_H: DS 1 ; RC pulse pre previous edge pca timestamp (hi byte)
  2248. Rcp_Edge_L: DS 1 ; RC pulse edge pca timestamp (lo byte)
  2249. Rcp_Edge_H: DS 1 ; RC pulse edge pca timestamp (hi byte)
  2250. Rcp_Prev_Period_L: DS 1 ; RC pulse previous period (lo byte)
  2251. Rcp_Prev_Period_H: DS 1 ; RC pulse previous period (hi byte)
  2252. Rcp_Period_Diff_Accepted: DS 1 ; RC pulse period difference acceptable
  2253. New_Rcp: DS 1 ; New RC pulse value in pca counts
  2254. Prev_Rcp_Pwm_Freq: DS 1 ; Previous RC pulse pwm frequency (used during pwm frequency measurement)
  2255. Curr_Rcp_Pwm_Freq: DS 1 ; Current RC pulse pwm frequency (used during pwm frequency measurement)
  2256. Rcp_Stop_Cnt: DS 1 ; Counter for RC pulses below stop value
  2257. Auto_Bailout_Armed: DS 1 ; Set when auto rotation bailout is armed
  2258. Pwm_Limit: DS 1 ; Maximum allowed pwm
  2259. Pwm_Limit_Spoolup: DS 1 ; Maximum allowed pwm during spoolup
  2260. Pwm_Limit_By_Rpm: DS 1 ; Maximum allowed pwm for low or high rpms
  2261. Pwm_Spoolup_Beg: DS 1 ; Pwm to begin main spoolup with
  2262. Pwm_Motor_Idle: DS 1 ; Motor idle speed pwm
  2263. Pwm_Dither_Decoded: DS 1 ; Decoded pwm dither value
  2264. Pwm_Dither_Excess_Power: DS 1 ; Excess power (above max) from pwm dither
  2265. Random: DS 1 ; Random number from LFSR
  2266. Spoolup_Limit_Cnt: DS 1 ; Interrupt count for spoolup limit
  2267. Spoolup_Limit_Skip: DS 1 ; Interrupt skips for spoolup limit increment (1=no skips, 2=skip one etc)
  2268. Main_Spoolup_Time_3x: DS 1 ; Main spoolup time x3
  2269. Main_Spoolup_Time_10x: DS 1 ; Main spoolup time x10
  2270. Main_Spoolup_Time_15x: DS 1 ; Main spoolup time x15
  2271. Lipo_Adc_Limit_L: DS 1 ; Low voltage limit adc value (lo byte)
  2272. Lipo_Adc_Limit_H: DS 1 ; Low voltage limit adc value (hi byte)
  2273. Adc_Conversion_Cnt: DS 1 ; Adc conversion counter
  2274. Current_Average_Temp: DS 1 ; Current average temperature (lo byte ADC reading, assuming hi byte is 1)
  2275. Ppm_Throttle_Gain: DS 1 ; Gain to be applied to RCP value for PPM input
  2276. Beep_Strength: DS 1 ; Strength of beeps
  2277. Tx_Pgm_Func_No: DS 1 ; Function number when doing programming by tx
  2278. Tx_Pgm_Paraval_No: DS 1 ; Parameter value number when doing programming by tx
  2279. Tx_Pgm_Beep_No: DS 1 ; Beep number when doing programming by tx
  2280. Skip_T2_Int: DS 1 ; Set for 48MHz MCUs when timer 2 interrupt shall be ignored
  2281. Skip_T2h_Int: DS 1 ; Set for 48MHz MCUs when timer 2 high interrupt shall be ignored
  2282. Timer0_Overflow_Value: DS 1 ; Remaining timer 0 wait time used with 48MHz MCUs
  2283. Clock_Set_At_48MHz: DS 1 ; Variable set if 48MHz MCUs run at 48MHz
  2284. DampingFET: DS 1 ; Port position of fet used for damping
  2285. Flash_Key_1: DS 1 ; Flash key one
  2286. Flash_Key_2: DS 1 ; Flash key two
  2287. ; Indirect addressing data segment. The variables below must be in this sequence
  2288. ISEG AT 080h
  2289. Pgm_Gov_P_Gain: DS 1 ; Programmed governor P gain
  2290. Pgm_Gov_I_Gain: DS 1 ; Programmed governor I gain
  2291. Pgm_Gov_Mode: DS 1 ; Programmed governor mode
  2292. Pgm_Low_Voltage_Lim: DS 1 ; Programmed low voltage limit
  2293. Pgm_Motor_Gain: DS 1 ; Programmed motor gain
  2294. Pgm_Motor_Idle: DS 1 ; Programmed motor idle speed
  2295. Pgm_Startup_Pwr: DS 1 ; Programmed startup power
  2296. Pgm_Pwm_Freq: DS 1 ; Programmed pwm frequency
  2297. Pgm_Direction: DS 1 ; Programmed rotation direction
  2298. Pgm_Input_Pol: DS 1 ; Programmed input pwm polarity
  2299. Initialized_L_Dummy: DS 1 ; Place holder
  2300. Initialized_H_Dummy: DS 1 ; Place holder
  2301. Pgm_Enable_TX_Program: DS 1 ; Programmed enable/disable value for TX programming
  2302. Pgm_Main_Rearm_Start: DS 1 ; Programmed enable/disable re-arming main every start
  2303. Pgm_Gov_Setup_Target: DS 1 ; Programmed main governor setup target
  2304. _Pgm_Startup_Rpm: DS 1 ; Programmed startup rpm (unused - place holder)
  2305. _Pgm_Startup_Accel: DS 1 ; Programmed startup acceleration (unused - place holder)
  2306. _Pgm_Volt_Comp: DS 1 ; Place holder
  2307. Pgm_Comm_Timing: DS 1 ; Programmed commutation timing
  2308. _Pgm_Damping_Force: DS 1 ; Programmed damping force (unused - place holder)
  2309. Pgm_Gov_Range: DS 1 ; Programmed governor range
  2310. _Pgm_Startup_Method: DS 1 ; Programmed startup method (unused - place holder)
  2311. Pgm_Ppm_Min_Throttle: DS 1 ; Programmed throttle minimum
  2312. Pgm_Ppm_Max_Throttle: DS 1 ; Programmed throttle maximum
  2313. Pgm_Beep_Strength: DS 1 ; Programmed beep strength
  2314. Pgm_Beacon_Strength: DS 1 ; Programmed beacon strength
  2315. Pgm_Beacon_Delay: DS 1 ; Programmed beacon delay
  2316. _Pgm_Throttle_Rate: DS 1 ; Programmed throttle rate (unused - place holder)
  2317. Pgm_Demag_Comp: DS 1 ; Programmed demag compensation
  2318. Pgm_BEC_Voltage_High: DS 1 ; Programmed BEC voltage
  2319. Pgm_Ppm_Center_Throttle: DS 1 ; Programmed throttle center (in bidirectional mode)
  2320. Pgm_Main_Spoolup_Time: DS 1 ; Programmed main spoolup time
  2321. Pgm_Enable_Temp_Prot: DS 1 ; Programmed temperature protection enable
  2322. Pgm_Enable_Power_Prot: DS 1 ; Programmed low rpm power protection enable
  2323. Pgm_Enable_Pwm_Input: DS 1 ; Programmed PWM input signal enable
  2324. Pgm_Pwm_Dither: DS 1 ; Programmed output PWM dither
  2325. Pgm_Brake_On_Stop: DS 1 ; Programmed braking when throttle is zero
  2326. ; The sequence of the variables below is no longer of importance
  2327. Pgm_Gov_P_Gain_Decoded: DS 1 ; Programmed governor decoded P gain
  2328. Pgm_Gov_I_Gain_Decoded: DS 1 ; Programmed governor decoded I gain
  2329. Pgm_Startup_Pwr_Decoded: DS 1 ; Programmed startup power decoded
  2330. ; Indirect addressing data segment
  2331. ISEG AT 0D0h
  2332. Tag_Temporary_Storage: DS 48 ; Temporary storage for tags when updating "Eeprom"
  2333. ;**** **** **** **** ****
  2334. CSEG AT 1A00h ; "Eeprom" segment
  2335. EEPROM_FW_MAIN_REVISION EQU 14 ; Main revision of the firmware
  2336. EEPROM_FW_SUB_REVISION EQU 9 ; Sub revision of the firmware
  2337. EEPROM_LAYOUT_REVISION EQU 21 ; Revision of the EEPROM layout
  2338. Eep_FW_Main_Revision: DB EEPROM_FW_MAIN_REVISION ; EEPROM firmware main revision number
  2339. Eep_FW_Sub_Revision: DB EEPROM_FW_SUB_REVISION ; EEPROM firmware sub revision number
  2340. Eep_Layout_Revision: DB EEPROM_LAYOUT_REVISION ; EEPROM layout revision number
  2341. IF MODE == 0
  2342. Eep_Pgm_Gov_P_Gain: DB DEFAULT_PGM_MAIN_P_GAIN ; EEPROM copy of programmed governor P gain
  2343. Eep_Pgm_Gov_I_Gain: DB DEFAULT_PGM_MAIN_I_GAIN ; EEPROM copy of programmed governor I gain
  2344. Eep_Pgm_Gov_Mode: DB DEFAULT_PGM_MAIN_GOVERNOR_MODE ; EEPROM copy of programmed governor mode
  2345. Eep_Pgm_Low_Voltage_Lim: DB DEFAULT_PGM_MAIN_LOW_VOLTAGE_LIM ; EEPROM copy of programmed low voltage limit
  2346. _Eep_Pgm_Motor_Gain: DB 0FFh
  2347. _Eep_Pgm_Motor_Idle: DB 0FFh
  2348. Eep_Pgm_Startup_Pwr: DB DEFAULT_PGM_MAIN_STARTUP_PWR ; EEPROM copy of programmed startup power
  2349. Eep_Pgm_Pwm_Freq: DB DEFAULT_PGM_MAIN_PWM_FREQ ; EEPROM copy of programmed pwm frequency
  2350. Eep_Pgm_Direction: DB DEFAULT_PGM_MAIN_DIRECTION ; EEPROM copy of programmed rotation direction
  2351. Eep_Pgm_Input_Pol: DB DEFAULT_PGM_MAIN_RCP_PWM_POL ; EEPROM copy of programmed input polarity
  2352. Eep_Initialized_L: DB 0A5h ; EEPROM initialized signature low byte
  2353. Eep_Initialized_H: DB 05Ah ; EEPROM initialized signature high byte
  2354. Eep_Enable_TX_Program: DB DEFAULT_PGM_ENABLE_TX_PROGRAM ; EEPROM TX programming enable
  2355. Eep_Main_Rearm_Start: DB DEFAULT_PGM_MAIN_REARM_START ; EEPROM re-arming main enable
  2356. Eep_Pgm_Gov_Setup_Target: DB DEFAULT_PGM_MAIN_GOV_SETUP_TARGET ; EEPROM main governor setup target
  2357. _Eep_Pgm_Startup_Rpm: DB 0FFh
  2358. _Eep_Pgm_Startup_Accel: DB 0FFh
  2359. _Eep_Pgm_Volt_Comp: DB 0FFh
  2360. Eep_Pgm_Comm_Timing: DB DEFAULT_PGM_MAIN_COMM_TIMING ; EEPROM copy of programmed commutation timing
  2361. _Eep_Pgm_Damping_Force: DB 0FFh
  2362. Eep_Pgm_Gov_Range: DB DEFAULT_PGM_MAIN_GOVERNOR_RANGE ; EEPROM copy of programmed governor range
  2363. _Eep_Pgm_Startup_Method: DB 0FFh
  2364. Eep_Pgm_Ppm_Min_Throttle: DB DEFAULT_PGM_PPM_MIN_THROTTLE ; EEPROM copy of programmed minimum throttle (final value is 4x+1000=1148)
  2365. Eep_Pgm_Ppm_Max_Throttle: DB DEFAULT_PGM_PPM_MAX_THROTTLE ; EEPROM copy of programmed minimum throttle (final value is 4x+1000=1832)
  2366. Eep_Pgm_Beep_Strength: DB DEFAULT_PGM_MAIN_BEEP_STRENGTH ; EEPROM copy of programmed beep strength
  2367. Eep_Pgm_Beacon_Strength: DB DEFAULT_PGM_MAIN_BEACON_STRENGTH ; EEPROM copy of programmed beacon strength
  2368. Eep_Pgm_Beacon_Delay: DB DEFAULT_PGM_MAIN_BEACON_DELAY ; EEPROM copy of programmed beacon delay
  2369. _Eep_Pgm_Throttle_Rate: DB 0FFh
  2370. Eep_Pgm_Demag_Comp: DB DEFAULT_PGM_MAIN_DEMAG_COMP ; EEPROM copy of programmed demag compensation
  2371. Eep_Pgm_BEC_Voltage_High: DB DEFAULT_PGM_BEC_VOLTAGE_HIGH ; EEPROM copy of programmed BEC voltage
  2372. _Eep_Pgm_Ppm_Center_Throttle: DB 0FFh
  2373. Eep_Pgm_Main_Spoolup_Time: DB DEFAULT_PGM_MAIN_SPOOLUP_TIME ; EEPROM copy of programmed main spoolup time
  2374. Eep_Pgm_Temp_Prot_Enable: DB DEFAULT_PGM_ENABLE_TEMP_PROT ; EEPROM copy of programmed temperature protection enable
  2375. Eep_Pgm_Enable_Power_Prot: DB DEFAULT_PGM_ENABLE_POWER_PROT ; EEPROM copy of programmed low rpm power protection enable
  2376. Eep_Pgm_Enable_Pwm_Input: DB DEFAULT_PGM_ENABLE_PWM_INPUT ; EEPROM copy of programmed PWM input signal enable
  2377. _Eep_Pgm_Pwm_Dither: DB 0FFh
  2378. Eep_Pgm_Brake_On_Stop: DB DEFAULT_PGM_BRAKE_ON_STOP ; EEPROM copy of programmed braking when throttle is zero
  2379. ENDIF
  2380. IF MODE == 1
  2381. _Eep_Pgm_Gov_P_Gain: DB 0FFh
  2382. _Eep_Pgm_Gov_I_Gain: DB 0FFh
  2383. _Eep_Pgm_Gov_Mode: DB 0FFh
  2384. _Eep_Pgm_Low_Voltage_Lim: DB 0FFh
  2385. Eep_Pgm_Motor_Gain: DB DEFAULT_PGM_TAIL_GAIN ; EEPROM copy of programmed tail gain
  2386. Eep_Pgm_Motor_Idle: DB DEFAULT_PGM_TAIL_IDLE_SPEED ; EEPROM copy of programmed tail idle speed
  2387. Eep_Pgm_Startup_Pwr: DB DEFAULT_PGM_TAIL_STARTUP_PWR ; EEPROM copy of programmed startup power
  2388. Eep_Pgm_Pwm_Freq: DB DEFAULT_PGM_TAIL_PWM_FREQ ; EEPROM copy of programmed pwm frequency
  2389. Eep_Pgm_Direction: DB DEFAULT_PGM_TAIL_DIRECTION ; EEPROM copy of programmed rotation direction
  2390. Eep_Pgm_Input_Pol: DB DEFAULT_PGM_TAIL_RCP_PWM_POL ; EEPROM copy of programmed input polarity
  2391. Eep_Initialized_L: DB 05Ah ; EEPROM initialized signature low byte
  2392. Eep_Initialized_H: DB 0A5h ; EEPROM initialized signature high byte
  2393. Eep_Enable_TX_Program: DB DEFAULT_PGM_ENABLE_TX_PROGRAM ; EEPROM TX programming enable
  2394. _Eep_Main_Rearm_Start: DB 0FFh
  2395. _Eep_Pgm_Gov_Setup_Target: DB 0FFh
  2396. _Eep_Pgm_Startup_Rpm: DB 0FFh
  2397. _Eep_Pgm_Startup_Accel: DB 0FFh
  2398. _Eep_Pgm_Volt_Comp: DB 0FFh
  2399. Eep_Pgm_Comm_Timing: DB DEFAULT_PGM_TAIL_COMM_TIMING ; EEPROM copy of programmed commutation timing
  2400. _Eep_Pgm_Damping_Force: DB 0FFh
  2401. _Eep_Pgm_Gov_Range: DB 0FFh
  2402. _Eep_Pgm_Startup_Method: DB 0FFh
  2403. Eep_Pgm_Ppm_Min_Throttle: DB DEFAULT_PGM_PPM_MIN_THROTTLE ; EEPROM copy of programmed minimum throttle (final value is 4x+1000=1148)
  2404. Eep_Pgm_Ppm_Max_Throttle: DB DEFAULT_PGM_PPM_MAX_THROTTLE ; EEPROM copy of programmed minimum throttle (final value is 4x+1000=1832)
  2405. Eep_Pgm_Beep_Strength: DB DEFAULT_PGM_TAIL_BEEP_STRENGTH ; EEPROM copy of programmed beep strength
  2406. Eep_Pgm_Beacon_Strength: DB DEFAULT_PGM_TAIL_BEACON_STRENGTH ; EEPROM copy of programmed beacon strength
  2407. Eep_Pgm_Beacon_Delay: DB DEFAULT_PGM_TAIL_BEACON_DELAY ; EEPROM copy of programmed beacon delay
  2408. _Eep_Pgm_Throttle_Rate: DB 0FFh
  2409. Eep_Pgm_Demag_Comp: DB DEFAULT_PGM_TAIL_DEMAG_COMP ; EEPROM copy of programmed demag compensation
  2410. Eep_Pgm_BEC_Voltage_High: DB DEFAULT_PGM_BEC_VOLTAGE_HIGH ; EEPROM copy of programmed BEC voltage
  2411. Eep_Pgm_Ppm_Center_Throttle: DB DEFAULT_PGM_PPM_CENTER_THROTTLE ; EEPROM copy of programmed center throttle (final value is 4x+1000=1488)
  2412. _Eep_Pgm_Main_Spoolup_Time: DB 0FFh
  2413. Eep_Pgm_Temp_Prot_Enable: DB DEFAULT_PGM_ENABLE_TEMP_PROT ; EEPROM copy of programmed temperature protection enable
  2414. Eep_Pgm_Enable_Power_Prot: DB DEFAULT_PGM_ENABLE_POWER_PROT ; EEPROM copy of programmed low rpm power protection enable
  2415. Eep_Pgm_Enable_Pwm_Input: DB DEFAULT_PGM_ENABLE_PWM_INPUT ; EEPROM copy of programmed PWM input signal enable
  2416. Eep_Pgm_Pwm_Dither: DB DEFAULT_PGM_TAIL_PWM_DITHER ; EEPROM copy of programmed output PWM dither
  2417. Eep_Pgm_Brake_On_Stop: DB DEFAULT_PGM_BRAKE_ON_STOP ; EEPROM copy of programmed braking when throttle is zero
  2418. ENDIF
  2419. IF MODE == 2
  2420. Eep_Pgm_Gov_P_Gain: DB DEFAULT_PGM_MULTI_P_GAIN ; EEPROM copy of programmed closed loop P gain
  2421. Eep_Pgm_Gov_I_Gain: DB DEFAULT_PGM_MULTI_I_GAIN ; EEPROM copy of programmed closed loop I gain
  2422. Eep_Pgm_Gov_Mode: DB DEFAULT_PGM_MULTI_GOVERNOR_MODE ; EEPROM copy of programmed closed loop mode
  2423. _Eep_Pgm_Low_Voltage_Lim: DB 0FFh
  2424. Eep_Pgm_Motor_Gain: DB DEFAULT_PGM_MULTI_GAIN ; EEPROM copy of programmed tail gain
  2425. _Eep_Pgm_Motor_Idle: DB 0FFh ; EEPROM copy of programmed tail idle speed
  2426. Eep_Pgm_Startup_Pwr: DB DEFAULT_PGM_MULTI_STARTUP_PWR ; EEPROM copy of programmed startup power
  2427. Eep_Pgm_Pwm_Freq: DB DEFAULT_PGM_MULTI_PWM_FREQ ; EEPROM copy of programmed pwm frequency
  2428. Eep_Pgm_Direction: DB DEFAULT_PGM_MULTI_DIRECTION ; EEPROM copy of programmed rotation direction
  2429. Eep_Pgm_Input_Pol: DB DEFAULT_PGM_MULTI_RCP_PWM_POL ; EEPROM copy of programmed input polarity
  2430. Eep_Initialized_L: DB 055h ; EEPROM initialized signature low byte
  2431. Eep_Initialized_H: DB 0AAh ; EEPROM initialized signature high byte
  2432. Eep_Enable_TX_Program: DB DEFAULT_PGM_ENABLE_TX_PROGRAM ; EEPROM TX programming enable
  2433. _Eep_Main_Rearm_Start: DB 0FFh
  2434. _Eep_Pgm_Gov_Setup_Target: DB 0FFh
  2435. _Eep_Pgm_Startup_Rpm: DB 0FFh
  2436. _Eep_Pgm_Startup_Accel: DB 0FFh
  2437. _Eep_Pgm_Volt_Comp: DB 0FFh
  2438. Eep_Pgm_Comm_Timing: DB DEFAULT_PGM_MULTI_COMM_TIMING ; EEPROM copy of programmed commutation timing
  2439. _Eep_Pgm_Damping_Force: DB 0FFh
  2440. _Eep_Pgm_Gov_Range: DB 0FFh
  2441. _Eep_Pgm_Startup_Method: DB 0FFh
  2442. Eep_Pgm_Ppm_Min_Throttle: DB DEFAULT_PGM_PPM_MIN_THROTTLE ; EEPROM copy of programmed minimum throttle (final value is 4x+1000=1148)
  2443. Eep_Pgm_Ppm_Max_Throttle: DB DEFAULT_PGM_PPM_MAX_THROTTLE ; EEPROM copy of programmed minimum throttle (final value is 4x+1000=1832)
  2444. Eep_Pgm_Beep_Strength: DB DEFAULT_PGM_MULTI_BEEP_STRENGTH ; EEPROM copy of programmed beep strength
  2445. Eep_Pgm_Beacon_Strength: DB DEFAULT_PGM_MULTI_BEACON_STRENGTH ; EEPROM copy of programmed beacon strength
  2446. Eep_Pgm_Beacon_Delay: DB DEFAULT_PGM_MULTI_BEACON_DELAY ; EEPROM copy of programmed beacon delay
  2447. _Eep_Pgm_Throttle_Rate: DB 0FFh
  2448. Eep_Pgm_Demag_Comp: DB DEFAULT_PGM_MULTI_DEMAG_COMP ; EEPROM copy of programmed demag compensation
  2449. Eep_Pgm_BEC_Voltage_High: DB DEFAULT_PGM_BEC_VOLTAGE_HIGH ; EEPROM copy of programmed BEC voltage
  2450. Eep_Pgm_Ppm_Center_Throttle: DB DEFAULT_PGM_PPM_CENTER_THROTTLE ; EEPROM copy of programmed center throttle (final value is 4x+1000=1488)
  2451. _Eep_Pgm_Main_Spoolup_Time: DB 0FFh
  2452. Eep_Pgm_Temp_Prot_Enable: DB DEFAULT_PGM_ENABLE_TEMP_PROT ; EEPROM copy of programmed temperature protection enable
  2453. Eep_Pgm_Enable_Power_Prot: DB DEFAULT_PGM_ENABLE_POWER_PROT ; EEPROM copy of programmed low rpm power protection enable
  2454. Eep_Pgm_Enable_Pwm_Input: DB DEFAULT_PGM_ENABLE_PWM_INPUT ; EEPROM copy of programmed PWM input signal enable
  2455. Eep_Pgm_Pwm_Dither: DB DEFAULT_PGM_MULTI_PWM_DITHER ; EEPROM copy of programmed output PWM dither
  2456. Eep_Pgm_Brake_On_Stop: DB DEFAULT_PGM_BRAKE_ON_STOP ; EEPROM copy of programmed braking when throttle is zero
  2457. ENDIF
  2458. Eep_Dummy: DB 0FFh ; EEPROM address for safety reason
  2459. CSEG AT 1A60h
  2460. Eep_Name: DB " " ; Name tag (16 Bytes)
  2461. ;**** **** **** **** ****
  2462. Interrupt_Table_Definition ; SiLabs interrupts
  2463. CSEG AT 80h ; Code segment after interrupt vectors
  2464. ;**** **** **** **** ****
  2465. ; Table definitions
  2466. GOV_GAIN_TABLE: DB 02h, 03h, 04h, 06h, 08h, 0Ch, 10h, 18h, 20h, 30h, 40h, 60h, 80h
  2467. STARTUP_POWER_TABLE: DB 04h, 06h, 08h, 0Ch, 10h, 18h, 20h, 30h, 40h, 60h, 80h, 0A0h, 0C0h
  2468. PWM_DITHER_TABLE: DB 00h, 03h, 07h, 0Fh, 1Fh
  2469. IF MODE == 0
  2470. IF DAMPED_MODE_ENABLE == 1
  2471. TX_PGM_PARAMS_MAIN: DB 13, 13, 4, 3, 6, 13, 5, 3, 3, 2, 2
  2472. ENDIF
  2473. IF DAMPED_MODE_ENABLE == 0
  2474. TX_PGM_PARAMS_MAIN: DB 13, 13, 4, 3, 6, 13, 5, 2, 3, 2, 2
  2475. ENDIF
  2476. ENDIF
  2477. IF MODE == 1
  2478. IF DAMPED_MODE_ENABLE == 1
  2479. TX_PGM_PARAMS_TAIL: DB 5, 5, 13, 5, 3, 5, 3, 3, 2
  2480. ENDIF
  2481. IF DAMPED_MODE_ENABLE == 0
  2482. TX_PGM_PARAMS_TAIL: DB 5, 5, 13, 5, 2, 5, 3, 3, 2
  2483. ENDIF
  2484. ENDIF
  2485. IF MODE == 2
  2486. IF DAMPED_MODE_ENABLE == 1
  2487. TX_PGM_PARAMS_MULTI: DB 13, 13, 4, 5, 13, 5, 3, 5, 3, 3, 2
  2488. ENDIF
  2489. IF DAMPED_MODE_ENABLE == 0
  2490. TX_PGM_PARAMS_MULTI: DB 13, 13, 4, 5, 13, 5, 2, 5, 3, 3, 2
  2491. ENDIF
  2492. ENDIF
  2493. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  2494. ;
  2495. ; Timer0 interrupt routine
  2496. ;
  2497. ; Assumptions: DPTR register must be set to desired pwm_nfet_on label
  2498. ; Requirements: Temp variables can NOT be used since PSW.3 is not set
  2499. ;
  2500. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  2501. t0_int: ; Used for pwm control
  2502. clr EA ; Disable all interrupts
  2503. IF MCU_48MHZ == 1
  2504. ; Check overflow flag
  2505. jnb Flags0.PWM_TIMER0_OVERFLOW, t0_int_start; Execute this interrupt
  2506. clr Flags0.PWM_TIMER0_OVERFLOW
  2507. mov TL0, Timer0_Overflow_Value ; Set timer
  2508. setb EA ; Enable all interrupts
  2509. reti
  2510. t0_int_start:
  2511. ENDIF
  2512. push PSW ; Preserve registers through interrupt
  2513. push ACC
  2514. ; Check if pwm is on
  2515. jb Flags0.PWM_ON, t0_int_pwm_off ; Is pwm on?
  2516. ; Pwm on cycle
  2517. mov A, Current_Pwm_Limited
  2518. jz t0_int_pwm_on_ret
  2519. clr A
  2520. jmp @A+DPTR ; Jump to pwm on routines. DPTR should be set to one of the pwm_nfet_on labels
  2521. t0_int_pwm_on_exit:
  2522. ; Set timer for coming on cycle length
  2523. mov A, Current_Pwm_Limited ; Load current pwm
  2524. cpl A ; cpl is 255-x
  2525. IF MCU_48MHZ == 0
  2526. mov TL0, A ; Write start point for timer
  2527. ELSE
  2528. clr C
  2529. rlc A
  2530. jc t0_int_pwm_on_set_timer
  2531. mov TL0, #0
  2532. setb Flags0.PWM_TIMER0_OVERFLOW
  2533. mov Timer0_Overflow_Value, A
  2534. ajmp t0_int_pwm_on_timer_set
  2535. t0_int_pwm_on_set_timer:
  2536. mov TL0, A
  2537. t0_int_pwm_on_timer_set:
  2538. ENDIF
  2539. ; Set other variables
  2540. setb Flags0.PWM_ON ; Set pwm on flag
  2541. t0_int_pwm_on_ret:
  2542. ; Exit interrupt
  2543. pop ACC ; Restore preserved registers
  2544. pop PSW
  2545. setb EA ; Enable all interrupts
  2546. reti
  2547. ; Pwm off cycle
  2548. t0_int_pwm_off:
  2549. IF MCU_48MHZ == 0
  2550. mov TL0, Current_Pwm_Lim_Dith ; Load new timer setting
  2551. ELSE
  2552. clr C
  2553. mov A, Current_Pwm_Lim_Dith
  2554. rlc A
  2555. jc t0_int_pwm_off_set_timer
  2556. mov TL0, #0
  2557. setb Flags0.PWM_TIMER0_OVERFLOW
  2558. mov Timer0_Overflow_Value, A
  2559. ajmp t0_int_pwm_off_timer_set
  2560. t0_int_pwm_off_set_timer:
  2561. mov TL0, A
  2562. t0_int_pwm_off_timer_set:
  2563. ENDIF
  2564. ; Clear pwm on flag
  2565. clr Flags0.PWM_ON
  2566. ; 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
  2567. mov A, Current_Pwm_Lim_Dith ; Load current pwm
  2568. cpl A ; Full pwm?
  2569. jz t0_int_pwm_off_fullpower_exit ; Yes - exit
  2570. IF DAMPED_MODE_ENABLE == 1
  2571. ; Do not execute pwm off when stopped
  2572. jnb Flags1.MOTOR_SPINNING, t0_int_pwm_off_exit
  2573. ; If damped operation, set pFETs on in pwm_off
  2574. jb Flags2.PGM_PWMOFF_DAMPED, t0_int_pwm_off_damped ; Damped operation?
  2575. ENDIF
  2576. t0_int_pwm_off_exit_nfets_off:
  2577. ; Separate exit commands here for minimum delay
  2578. IF NFETON_DELAY == 0
  2579. En_Off ; For EN/PWM style drivers. Uses accumulator
  2580. ENDIF
  2581. pop ACC ; Restore preserved registers
  2582. pop PSW
  2583. IF NFETON_DELAY NE 0
  2584. All_nFETs_Off ; Switch off all nfets
  2585. ENDIF
  2586. setb EA ; Enable all interrupts
  2587. reti
  2588. t0_int_pwm_off_damped:
  2589. IF PFETON_DELAY < 128
  2590. IF PFETON_DELAY NE 0
  2591. All_nFETs_Off ; Switch off all nfets
  2592. ELSE
  2593. En_Off
  2594. ENDIF
  2595. jb Flags1.SKIP_DAMP_ON, t0_int_pwm_off_damp_done
  2596. jb Flags0.DEMAG_CUT_POWER, t0_int_pwm_off_damp_done
  2597. IF PFETON_DELAY NE 0
  2598. mov A, #PFETON_DELAY
  2599. djnz ACC, $
  2600. ENDIF
  2601. Damping_FET_on
  2602. t0_int_pwm_off_damp_done:
  2603. ENDIF
  2604. IF PFETON_DELAY >= 128 ; "Negative", 1's complement
  2605. jb Flags1.SKIP_DAMP_ON, t0_int_pwm_off_damp_done
  2606. jb Flags0.DEMAG_CUT_POWER, t0_int_pwm_off_damp_done
  2607. Damping_FET_on ; Damping fet on
  2608. mov A, #PFETON_DELAY
  2609. cpl A
  2610. djnz ACC, $
  2611. t0_int_pwm_off_damp_done:
  2612. All_nFETs_Off ; Switch off all nfets
  2613. ENDIF
  2614. t0_int_pwm_off_exit:
  2615. pop ACC ; Restore preserved registers
  2616. pop PSW
  2617. setb EA ; Enable all interrupts
  2618. reti
  2619. t0_int_pwm_off_fullpower_exit:
  2620. mov TL0, #0 ; Set long time till next interrupt
  2621. IF MCU_48MHZ == 1
  2622. setb Flags0.PWM_TIMER0_OVERFLOW
  2623. mov Timer0_Overflow_Value, #0
  2624. ENDIF
  2625. clr TF0 ; Clear interrupt flag
  2626. setb Flags0.PWM_ON
  2627. ajmp t0_int_pwm_off_exit
  2628. pwm_nofet: ; Dummy pwm on cycle
  2629. ajmp t0_int_pwm_on_exit
  2630. pwm_afet: ; Pwm on cycle afet on
  2631. jnb Flags1.MOTOR_SPINNING, pwm_afet_exit
  2632. jb Flags0.DEMAG_CUT_POWER, pwm_afet_exit
  2633. AnFET_on
  2634. pwm_afet_exit:
  2635. ajmp t0_int_pwm_on_exit
  2636. pwm_bfet: ; Pwm on cycle bfet on
  2637. jnb Flags1.MOTOR_SPINNING, pwm_bfet_exit
  2638. jb Flags0.DEMAG_CUT_POWER, pwm_bfet_exit
  2639. BnFET_on
  2640. pwm_bfet_exit:
  2641. ajmp t0_int_pwm_on_exit
  2642. pwm_cfet: ; Pwm on cycle cfet on
  2643. jnb Flags1.MOTOR_SPINNING, pwm_cfet_exit
  2644. jb Flags0.DEMAG_CUT_POWER, pwm_cfet_exit
  2645. CnFET_on
  2646. pwm_cfet_exit:
  2647. ajmp t0_int_pwm_on_exit
  2648. pwm_afet_damped:
  2649. IF NFETON_DELAY NE 0
  2650. ApFET_off
  2651. ENDIF
  2652. jnb Flags1.MOTOR_SPINNING, pwm_afet_damped_exit
  2653. jb Flags0.DEMAG_CUT_POWER, pwm_afet_damped_exit
  2654. IF NFETON_DELAY NE 0
  2655. mov A, #NFETON_DELAY ; Set delay
  2656. djnz ACC, $
  2657. ENDIF
  2658. pwm_afet_damped_done:
  2659. AnFET_on ; Switch nFET
  2660. pwm_afet_damped_exit:
  2661. ajmp t0_int_pwm_on_exit
  2662. pwm_bfet_damped:
  2663. IF NFETON_DELAY NE 0
  2664. BpFET_off
  2665. ENDIF
  2666. jnb Flags1.MOTOR_SPINNING, pwm_bfet_damped_exit
  2667. jb Flags0.DEMAG_CUT_POWER, pwm_bfet_damped_exit
  2668. IF NFETON_DELAY NE 0
  2669. mov A, #NFETON_DELAY ; Set delay
  2670. djnz ACC, $
  2671. ENDIF
  2672. pwm_bfet_damped_done:
  2673. BnFET_on ; Switch nFET
  2674. pwm_bfet_damped_exit:
  2675. ajmp t0_int_pwm_on_exit
  2676. pwm_cfet_damped:
  2677. IF NFETON_DELAY NE 0
  2678. CpFET_off
  2679. ENDIF
  2680. jnb Flags1.MOTOR_SPINNING, pwm_cfet_damped_exit
  2681. jb Flags0.DEMAG_CUT_POWER, pwm_cfet_damped_exit
  2682. IF NFETON_DELAY NE 0
  2683. mov A, #NFETON_DELAY ; Set delay
  2684. djnz ACC, $
  2685. ENDIF
  2686. pwm_cfet_damped_done:
  2687. CnFET_on ; Switch nFET
  2688. pwm_cfet_damped_exit:
  2689. ajmp t0_int_pwm_on_exit
  2690. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  2691. ;
  2692. ; Timer2 interrupt routine
  2693. ;
  2694. ; No assumptions
  2695. ;
  2696. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  2697. t2_int: ; Happens every 128us for low byte and every 32ms for high byte
  2698. clr EA
  2699. clr ET2 ; Disable timer2 interrupts
  2700. anl EIE1, #0EFh ; Disable PCA0 interrupts
  2701. push PSW ; Preserve registers through interrupt
  2702. push ACC
  2703. setb PSW.3 ; Select register bank 1 for interrupt routines
  2704. setb EA
  2705. IF MCU_48MHZ == 1
  2706. mov A, Clock_Set_At_48MHz
  2707. jz t2_int_start
  2708. ; Check skip variable
  2709. mov A, Skip_T2_Int
  2710. jz t2_int_start ; Execute this interrupt
  2711. mov Skip_T2_Int, #0
  2712. ajmp t2_int_exit
  2713. t2_int_start:
  2714. mov Skip_T2_Int, #1 ; Skip next interrupt
  2715. ENDIF
  2716. ; Clear low byte interrupt flag
  2717. clr TF2L ; Clear interrupt flag
  2718. ; Check RC pulse timeout counter
  2719. mov A, Rcp_Timeout_Cntd ; RC pulse timeout count zero?
  2720. jz t2_int_pulses_absent ; Yes - pulses are absent
  2721. ; Decrement timeout counter (if PWM)
  2722. jb Flags2.RCP_PPM, t2_int_skip_start ; If flag is set (PPM) - branch
  2723. dec Rcp_Timeout_Cntd ; No - decrement
  2724. ajmp t2_int_skip_start
  2725. t2_int_pulses_absent:
  2726. ; Timeout counter has reached zero, pulses are absent
  2727. mov Temp1, #RCP_MIN ; RCP_MIN as default
  2728. mov Temp2, #RCP_MIN
  2729. jb Flags2.RCP_PPM, t2_int_pulses_absent_no_max ; If flag is set (PPM) - branch
  2730. Read_Rcp_Int ; Look at value of Rcp_In
  2731. jnb ACC.Rcp_In, ($+5) ; Is it high?
  2732. mov Temp1, #RCP_MAX ; Yes - set RCP_MAX
  2733. Rcp_Int_First ; Set interrupt trig to first again
  2734. Rcp_Clear_Int_Flag ; Clear interrupt flag
  2735. clr Flags2.RCP_EDGE_NO ; Set first edge flag
  2736. Read_Rcp_Int ; Look once more at value of Rcp_In
  2737. jnb ACC.Rcp_In, ($+5) ; Is it high?
  2738. mov Temp2, #RCP_MAX ; Yes - set RCP_MAX
  2739. clr C
  2740. mov A, Temp1
  2741. subb A, Temp2 ; Compare the two readings of Rcp_In
  2742. jnz t2_int_pulses_absent ; Go back if they are not equal
  2743. t2_int_pulses_absent_no_max:
  2744. jnb Flags0.RCP_MEAS_PWM_FREQ, ($+6) ; Is measure RCP pwm frequency flag set?
  2745. mov Rcp_Timeout_Cntd, #RCP_TIMEOUT ; Yes - set timeout count to start value
  2746. jb Flags2.RCP_PPM, t2_int_ppm_timeout_set ; If flag is set (PPM) - branch
  2747. mov Rcp_Timeout_Cntd, #RCP_TIMEOUT ; For PWM, set timeout count to start value
  2748. t2_int_ppm_timeout_set:
  2749. mov New_Rcp, Temp1 ; Store new pulse length
  2750. setb Flags2.RCP_UPDATED ; Set updated flag
  2751. ; Check if zero
  2752. mov A, Temp1 ; Load new pulse value
  2753. jz ($+5) ; Check if pulse is zero
  2754. mov Rcp_Stop_Cnt, #0 ; Reset rcp stop counter
  2755. t2_int_skip_start:
  2756. jb Flags2.RCP_PPM, t2_int_rcp_update_start ; If flag is set (PPM) - branch
  2757. ; Check RC pulse skip counter
  2758. mov A, Rcp_Skip_Cntd
  2759. jz t2_int_skip_end ; If RC pulse skip count is zero - end skipping RC pulse detection
  2760. ; Decrement skip counter (only if edge counter is zero)
  2761. dec Rcp_Skip_Cntd ; Decrement
  2762. ajmp t2_int_rcp_update_start
  2763. t2_int_skip_end:
  2764. ; Skip counter has reached zero, start looking for RC pulses again
  2765. Rcp_Int_Enable ; Enable RC pulse interrupt
  2766. Rcp_Clear_Int_Flag ; Clear interrupt flag
  2767. t2_int_rcp_update_start:
  2768. ; Process updated RC pulse
  2769. jb Flags2.RCP_UPDATED, ($+5) ; Is there an updated RC pulse available?
  2770. ajmp t2_int_current_pwm_update ; No - update pwm limits and exit
  2771. mov Temp1, New_Rcp ; Load new pulse value
  2772. jb Flags0.RCP_MEAS_PWM_FREQ, ($+5) ; If measure RCP pwm frequency flag set - do not clear flag
  2773. clr Flags2.RCP_UPDATED ; Flag that pulse has been evaluated
  2774. ; Use a gain of 1.0625x for pwm input if not governor mode
  2775. jb Flags2.RCP_PPM, t2_int_pwm_min_run ; If flag is set (PPM) - branch
  2776. IF MODE == 0 ; Main - do not adjust gain
  2777. ajmp t2_int_pwm_min_run
  2778. ELSE
  2779. IF MODE == 2 ; Multi
  2780. mov Temp2, #Pgm_Gov_Mode ; Closed loop mode?
  2781. cjne @Temp2, #4, t2_int_pwm_min_run; Yes - branch
  2782. ENDIF
  2783. ; Limit the maximum value to avoid wrap when scaled to pwm range
  2784. clr C
  2785. mov A, Temp1
  2786. subb A, #240 ; 240 = (255/1.0625) Needs to be updated according to multiplication factor below
  2787. jc t2_int_rcp_update_mult
  2788. mov A, #240 ; Set requested pwm to max
  2789. mov Temp1, A
  2790. t2_int_rcp_update_mult:
  2791. ; Multiply by 1.0625 (optional adjustment gyro gain)
  2792. mov A, Temp1
  2793. swap A ; After this "0.0625"
  2794. anl A, #0Fh
  2795. add A, Temp1
  2796. mov Temp1, A
  2797. ; Adjust tail gain
  2798. mov Temp2, #Pgm_Motor_Gain
  2799. cjne @Temp2, #3, ($+5) ; Is gain 1?
  2800. ajmp t2_int_pwm_min_run ; Yes - skip adjustment
  2801. clr C
  2802. rrc A ; After this "0.5"
  2803. clr C
  2804. rrc A ; After this "0.25"
  2805. mov Bit_Access_Int, @Temp2 ; (Temp2 has #Pgm_Motor_Gain)
  2806. jb Bit_Access_Int.0, t2_int_rcp_gain_corr ; Branch if bit 0 in gain is set
  2807. clr C
  2808. rrc A ; After this "0.125"
  2809. t2_int_rcp_gain_corr:
  2810. jb Bit_Access_Int.2, t2_int_rcp_gain_pos ; Branch if bit 2 in gain is set
  2811. clr C
  2812. xch A, Temp1
  2813. subb A, Temp1 ; Apply negative correction
  2814. mov Temp1, A
  2815. ajmp t2_int_pwm_min_run
  2816. t2_int_rcp_gain_pos:
  2817. add A, Temp1 ; Apply positive correction
  2818. mov Temp1, A
  2819. jnc t2_int_pwm_min_run ; Above max?
  2820. mov A, #0FFh ; Yes - limit
  2821. mov Temp1, A
  2822. ENDIF
  2823. t2_int_pwm_min_run:
  2824. IF MODE == 1 ; Tail - limit minimum pwm
  2825. ; Limit minimum pwm
  2826. clr C
  2827. mov A, Temp1
  2828. subb A, Pwm_Motor_Idle ; Is requested pwm lower than minimum?
  2829. jnc t2_int_pwm_update ; No - branch
  2830. mov A, Pwm_Motor_Idle ; Yes - limit pwm to Pwm_Motor_Idle
  2831. mov Temp1, A
  2832. ENDIF
  2833. t2_int_pwm_update:
  2834. ; Update requested_pwm
  2835. mov Requested_Pwm, Temp1 ; Set requested pwm
  2836. IF MODE >= 1 ; Tail or multi
  2837. ; Boost pwm during direct start
  2838. mov A, Flags1
  2839. anl A, #((1 SHL STARTUP_PHASE)+(1 SHL INITIAL_RUN_PHASE))
  2840. jz t2_int_current_pwm_update
  2841. jb Flags1.MOTOR_STARTED, t2_int_current_pwm_update ; Do not boost when changing direction in bidirectional mode
  2842. mov A, Stall_Cnt ; Add an extra power boost for each attempt
  2843. clr C
  2844. rlc A
  2845. clr C
  2846. rlc A
  2847. mov Temp1, A
  2848. mov A, Pwm_Spoolup_Beg ; Set 25% of max startup power as minimum power
  2849. clr C
  2850. rrc A
  2851. clr C
  2852. rrc A
  2853. mov Temp2, A
  2854. clr C
  2855. subb A, Requested_Pwm
  2856. jc ($+4)
  2857. mov Requested_Pwm, Temp2
  2858. mov A, Temp1
  2859. add A, Requested_Pwm
  2860. mov Requested_Pwm, A
  2861. jnc ($+5)
  2862. mov Requested_Pwm, #0FFh
  2863. ENDIF
  2864. t2_int_current_pwm_update:
  2865. IF MODE == 0 OR MODE == 2 ; Main or multi
  2866. mov Temp1, #Pgm_Gov_Mode ; Governor mode?
  2867. cjne @Temp1, #4, t2_int_exit ; Yes - branch
  2868. ENDIF
  2869. mov Current_Pwm, Requested_Pwm ; Set equal as default
  2870. IF MODE >= 1 ; Tail or multi
  2871. ; Set current_pwm_limited
  2872. mov Temp1, Current_Pwm ; Default not limited
  2873. clr C
  2874. mov A, Current_Pwm ; Check against limit
  2875. subb A, Pwm_Limit
  2876. jc ($+4) ; If current pwm below limit - branch
  2877. mov Temp1, Pwm_Limit ; Limit pwm
  2878. IF MODE == 2 ; Multi
  2879. ; Limit pwm for low rpms
  2880. clr C
  2881. mov A, Temp1 ; Check against limit
  2882. subb A, Pwm_Limit_By_Rpm
  2883. jc ($+4) ; If current pwm below limit - branch
  2884. mov Temp1, Pwm_Limit_By_Rpm ; Limit pwm
  2885. ENDIF
  2886. mov Current_Pwm_Limited, Temp1
  2887. ; Dither
  2888. mov A, Pwm_Dither_Decoded ; Load pwm dither
  2889. jnz ($+4) ; If active - branch
  2890. ajmp t2_int_current_pwm_no_dither
  2891. clr C
  2892. mov A, Temp1
  2893. mov Temp3, Pwm_Dither_Decoded
  2894. subb A, Temp3 ; Calculate pwm minus dither value
  2895. jnc t2_int_current_pwm_full_dither; If pwm more than dither value, then do full dither
  2896. mov A, Temp1 ; Set dither level to current pwm
  2897. mov Temp3, A
  2898. clr A ; Set pwm minus dither
  2899. t2_int_current_pwm_full_dither:
  2900. mov Temp2, A ; Load pwm minus dither value
  2901. mov A, Temp3 ; Load dither
  2902. clr C
  2903. rlc A ; Shift left once
  2904. mov Temp4, A
  2905. mov A, Random ; Load random number
  2906. cpl A ; Invert to create proper DC bias in random code
  2907. anl A, Temp4 ; And with double dither value
  2908. add A, Temp2 ; Add pwm minus dither
  2909. jc t2_int_current_pwm_dither_max_excess_power ; If dither cause power above max - branch and increase excess
  2910. add A, Pwm_Dither_Excess_Power ; Add excess power from previous cycles
  2911. mov Temp1, A
  2912. mov A, Pwm_Dither_Excess_Power ; Decrement excess power
  2913. jz ($+4)
  2914. dec Pwm_Dither_Excess_Power
  2915. jc t2_int_current_pwm_dither_max_power; If dither cause power above max - branch
  2916. ajmp t2_int_current_pwm_no_dither
  2917. t2_int_current_pwm_dither_max_excess_power:
  2918. inc Temp3 ; Add one to dither in order to always reach max power
  2919. clr C
  2920. mov A, Pwm_Dither_Excess_Power
  2921. subb A, Temp3 ; Limit excess power
  2922. jnc ($+4)
  2923. inc Pwm_Dither_Excess_Power
  2924. t2_int_current_pwm_dither_max_power:
  2925. mov Temp1, #255 ; Set power to max
  2926. t2_int_current_pwm_no_dither:
  2927. mov Current_Pwm_Lim_Dith, Temp1
  2928. IF DAMPED_MODE_ENABLE == 1
  2929. ; Skip damping fet switching for high throttle
  2930. clr Flags1.SKIP_DAMP_ON
  2931. clr C
  2932. mov A, Current_Pwm_Lim_Dith
  2933. subb A, #248
  2934. jc t2_int_exit
  2935. setb Flags1.SKIP_DAMP_ON
  2936. ENDIF
  2937. ENDIF
  2938. t2_int_exit:
  2939. ; Check if high byte flag is set
  2940. jb TF2H, t2h_int
  2941. pop ACC ; Restore preserved registers
  2942. pop PSW
  2943. orl EIE1, #10h ; Enable PCA0 interrupts
  2944. setb ET2 ; Enable timer2 interrupts
  2945. reti
  2946. t2h_int:
  2947. ; High byte interrupt (happens every 32ms)
  2948. clr TF2H ; Clear interrupt flag
  2949. inc Timer2_X
  2950. IF MCU_48MHZ == 1
  2951. mov A, Clock_Set_At_48MHz
  2952. jz t2h_int_start
  2953. ; Check skip variable
  2954. mov A, Skip_T2h_Int
  2955. jz t2h_int_start ; Execute this interrupt
  2956. mov Skip_T2h_Int, #0
  2957. ajmp t2h_int_exit
  2958. t2h_int_start:
  2959. mov Skip_T2h_Int, #1 ; Skip next interrupt
  2960. ENDIF
  2961. mov Temp1, #GOV_SPOOLRATE ; Load governor spool rate
  2962. ; Check RC pulse timeout counter (used here for PPM only)
  2963. mov A, Rcp_Timeout_Cntd ; RC pulse timeout count zero?
  2964. jz t2h_int_rcp_stop_check ; Yes - do not decrement
  2965. ; Decrement timeout counter (if PPM)
  2966. jnb Flags2.RCP_PPM, t2h_int_rcp_stop_check ; If flag is not set (PWM) - branch
  2967. dec Rcp_Timeout_Cntd ; No flag set (PPM) - decrement
  2968. t2h_int_rcp_stop_check:
  2969. ; Check RC pulse against stop value
  2970. clr C
  2971. mov A, New_Rcp ; Load new pulse value
  2972. subb A, #RCP_STOP ; Check if pulse is below stop value
  2973. jc t2h_int_rcp_stop
  2974. ; RC pulse higher than stop value, reset stop counter
  2975. mov Rcp_Stop_Cnt, #0 ; Reset rcp stop counter
  2976. ajmp t2h_int_rcp_gov_pwm
  2977. t2h_int_rcp_stop:
  2978. ; RC pulse less than stop value
  2979. mov Auto_Bailout_Armed, #0 ; Disarm bailout
  2980. mov Spoolup_Limit_Cnt, #0
  2981. mov A, Rcp_Stop_Cnt ; Increment stop counter
  2982. add A, #1
  2983. mov Rcp_Stop_Cnt, A
  2984. jnc t2h_int_rcp_gov_pwm ; Branch if counter has not wrapped
  2985. mov Rcp_Stop_Cnt, #0FFh ; Set stop counter to max
  2986. t2h_int_rcp_gov_pwm:
  2987. IF MODE == 0 ; Main
  2988. ; Update governor variables
  2989. mov Temp2, #Pgm_Gov_Mode ; Governor target by arm mode?
  2990. cjne @Temp2, #2, t2h_int_rcp_gov_by_setup ; No - branch
  2991. jnb Flags1.GOV_ACTIVE, t2h_int_rcp_gov_by_tx; If governor not active - branch (this ensures soft spoolup by tx)
  2992. clr C
  2993. mov A, Requested_Pwm
  2994. subb A, #50 ; Is requested pwm below 20%?
  2995. jc t2h_int_rcp_gov_by_tx ; Yes - branch (this enables a soft spooldown)
  2996. mov Requested_Pwm, Gov_Arm_Target ; Yes - load arm target
  2997. t2h_int_rcp_gov_by_setup:
  2998. mov Temp2, #Pgm_Gov_Mode ; Governor target by setup mode?
  2999. cjne @Temp2, #3, t2h_int_rcp_gov_by_tx ; No - branch
  3000. jnb Flags1.GOV_ACTIVE, t2h_int_rcp_gov_by_tx; If governor not active - branch (this ensures soft spoolup by tx)
  3001. clr C
  3002. mov A, Requested_Pwm
  3003. subb A, #50 ; Is requested pwm below 20%?
  3004. jc t2h_int_rcp_gov_by_tx ; Yes - branch (this enables a soft spooldown)
  3005. mov Temp2, #Pgm_Gov_Setup_Target ; Gov by setup - load setup target
  3006. mov Requested_Pwm, @Temp2
  3007. t2h_int_rcp_gov_by_tx:
  3008. clr C
  3009. mov A, Governor_Req_Pwm
  3010. subb A, Requested_Pwm ; Is governor requested pwm equal to requested pwm?
  3011. jz t2h_int_rcp_gov_pwm_done ; Yes - branch
  3012. jc t2h_int_rcp_gov_pwm_inc ; No - if lower, then increment
  3013. dec Governor_Req_Pwm ; No - if higher, then decrement
  3014. ajmp t2h_int_rcp_gov_pwm_done
  3015. t2h_int_rcp_gov_pwm_inc:
  3016. inc Governor_Req_Pwm ; Increment
  3017. t2h_int_rcp_gov_pwm_done:
  3018. djnz Temp1, t2h_int_rcp_gov_pwm ; If not number of steps processed - go back
  3019. inc Spoolup_Limit_Cnt ; Increment spoolup count
  3020. mov A, Spoolup_Limit_Cnt
  3021. jnz ($+4) ; Wrapped?
  3022. dec Spoolup_Limit_Cnt ; Yes - decrement
  3023. djnz Spoolup_Limit_Skip, t2h_int_exit ; Jump if skip count is not reached
  3024. mov Spoolup_Limit_Skip, #1 ; Reset skip count. Default is fast spoolup
  3025. mov Temp1, #8 ; Default fast increase for spoolup time of zero
  3026. mov A, Main_Spoolup_Time_3x
  3027. jz t2h_int_rcp_inc_limit ; Jump for spoolup time of zero
  3028. mov Temp1, #5 ; Default fast increase
  3029. clr C
  3030. mov A, Spoolup_Limit_Cnt
  3031. subb A, Main_Spoolup_Time_3x ; No spoolup until 3*N*32ms
  3032. jc t2h_int_exit
  3033. clr C
  3034. mov A, Spoolup_Limit_Cnt
  3035. subb A, Main_Spoolup_Time_10x ; Slow spoolup until "100"*N*32ms
  3036. jnc t2h_int_rcp_limit_middle_ramp
  3037. mov Temp1, #1 ; Slow initial spoolup
  3038. mov Spoolup_Limit_Skip, #3
  3039. jmp t2h_int_rcp_set_limit
  3040. t2h_int_rcp_limit_middle_ramp:
  3041. clr C
  3042. mov A, Spoolup_Limit_Cnt
  3043. subb A, Main_Spoolup_Time_15x ; Faster spoolup until "150"*N*32ms
  3044. jnc t2h_int_rcp_set_limit
  3045. mov Temp1, #1 ; Faster middle spoolup
  3046. mov Spoolup_Limit_Skip, #1
  3047. t2h_int_rcp_set_limit:
  3048. ; Do not increment spoolup limit if higher pwm is not requested, unless governor is active
  3049. clr C
  3050. mov A, Pwm_Limit_Spoolup
  3051. subb A, Current_Pwm
  3052. jc t2h_int_rcp_inc_limit ; If Current_Pwm is larger than Pwm_Limit_Spoolup - branch
  3053. mov Temp2, #Pgm_Gov_Mode ; Governor mode?
  3054. cjne @Temp2, #4, ($+5)
  3055. ajmp t2h_int_rcp_bailout_arm ; No - branch
  3056. jb Flags1.GOV_ACTIVE, t2h_int_rcp_inc_limit ; If governor active - branch
  3057. mov Pwm_Limit_Spoolup, Current_Pwm ; Set limit to what current pwm is
  3058. mov A, Spoolup_Limit_Cnt ; Check if spoolup limit count is 255. If it is, then this is a "bailout" ramp
  3059. inc A
  3060. jz ($+5)
  3061. mov Spoolup_Limit_Cnt, Main_Spoolup_Time_3x ; Stay in an early part of the spoolup sequence (unless "bailout" ramp)
  3062. mov Spoolup_Limit_Skip, #1 ; Set skip count
  3063. mov Governor_Req_Pwm, #60 ; Set governor requested speed to ensure that it requests higher speed
  3064. ; 20=Fail on jerk when governor activates
  3065. ; 30=Ok
  3066. ; 100=Fail on small governor settling overshoot on low headspeeds
  3067. ; 200=Fail on governor settling overshoot
  3068. jmp t2h_int_exit ; Exit
  3069. t2h_int_rcp_inc_limit:
  3070. mov A, Pwm_Limit_Spoolup ; Increment spoolup pwm
  3071. add A, Temp1
  3072. jnc t2h_int_rcp_no_limit ; If below 255 - branch
  3073. mov Pwm_Limit_Spoolup, #0FFh
  3074. ajmp t2h_int_rcp_bailout_arm
  3075. t2h_int_rcp_no_limit:
  3076. mov Pwm_Limit_Spoolup, A
  3077. t2h_int_rcp_bailout_arm:
  3078. mov A, Pwm_Limit_Spoolup
  3079. inc A
  3080. jnz t2h_int_exit
  3081. mov Auto_Bailout_Armed, #255 ; Arm bailout
  3082. mov Spoolup_Limit_Cnt, #255
  3083. ENDIF
  3084. t2h_int_exit:
  3085. pop ACC ; Restore preserved registers
  3086. pop PSW
  3087. orl EIE1, #10h ; Enable PCA0 interrupts
  3088. setb ET2 ; Enable timer2 interrupts
  3089. reti
  3090. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  3091. ;
  3092. ; Timer3 interrupt routine
  3093. ;
  3094. ; No assumptions
  3095. ;
  3096. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  3097. t3_int: ; Used for commutation timing
  3098. clr EA ; Disable all interrupts
  3099. anl EIE1, #7Fh ; Disable timer3 interrupts
  3100. mov TMR3RLL, #0FAh ; Set a short delay before next interrupt
  3101. mov TMR3RLH, #0FFh
  3102. clr Flags0.T3_PENDING ; Flag that timer has wrapped
  3103. mov TMR3CN, #04h ; Timer3 enabled and interrupt flag cleared
  3104. setb EA ; Enable all interrupts
  3105. reti
  3106. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  3107. ;
  3108. ; PCA interrupt routine
  3109. ;
  3110. ; No assumptions
  3111. ;
  3112. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  3113. pca_int: ; Used for RC pulse timing
  3114. clr EA
  3115. anl EIE1, #0EFh ; Disable PCA0 interrupts
  3116. clr ET2 ; Disable timer2 interrupts
  3117. push PSW ; Preserve registers through interrupt
  3118. push ACC
  3119. push B
  3120. setb PSW.3 ; Select register bank 1 for interrupt routines
  3121. setb EA
  3122. ; Get the PCA counter values
  3123. Get_Rcp_Capture_Values
  3124. ; Clear interrupt flag
  3125. Rcp_Clear_Int_Flag
  3126. ; Check which edge it is
  3127. jnb Flags2.RCP_EDGE_NO, ($+5) ; Is it a first edge trig?
  3128. ajmp pca_int_second_meas_pwm_freq ; No - branch to second
  3129. Rcp_Int_Second ; Yes - set second edge trig
  3130. setb Flags2.RCP_EDGE_NO ; Set second edge flag
  3131. ; Read RC signal level
  3132. Read_Rcp_Int
  3133. ; Test RC signal level
  3134. jb ACC.Rcp_In, ($+5) ; Is it high?
  3135. ajmp pca_int_fail_minimum ; No - jump to fail minimum
  3136. ; RC pulse was high, store RC pulse start timestamp
  3137. mov Rcp_Prev_Edge_L, Temp1
  3138. mov Rcp_Prev_Edge_H, Temp2
  3139. ajmp pca_int_exit ; Exit
  3140. pca_int_fail_minimum:
  3141. ; Prepare for next interrupt
  3142. Rcp_Int_First ; Set interrupt trig to first again
  3143. Rcp_Clear_Int_Flag ; Clear interrupt flag
  3144. clr Flags2.RCP_EDGE_NO ; Set first edge flag
  3145. jnb Flags2.RCP_PPM, ($+5) ; If flag is not set (PWM) - branch
  3146. ajmp pca_int_set_timeout ; If PPM - ignore trig as noise
  3147. mov Temp1, #RCP_MIN ; Set RC pulse value to minimum
  3148. Read_Rcp_Int ; Test RC signal level again
  3149. jnb ACC.Rcp_In, ($+5) ; Is it high?
  3150. ajmp pca_int_set_timeout ; Yes - set new timeout and exit
  3151. mov New_Rcp, Temp1 ; Store new pulse length
  3152. ajmp pca_int_limited ; Set new RC pulse, new timeout and exit
  3153. pca_int_second_meas_pwm_freq:
  3154. ; Prepare for next interrupt
  3155. Rcp_Int_First ; Set first edge trig
  3156. clr Flags2.RCP_EDGE_NO ; Set first edge flag
  3157. ; Check if pwm frequency shall be measured
  3158. jb Flags0.RCP_MEAS_PWM_FREQ, ($+5) ; Is measure RCP pwm frequency flag set?
  3159. ajmp pca_int_fall ; No - skip measurements
  3160. ; Set second edge trig only during pwm frequency measurement
  3161. Rcp_Int_Second ; Set second edge trig
  3162. Rcp_Clear_Int_Flag ; Clear interrupt flag
  3163. setb Flags2.RCP_EDGE_NO ; Set second edge flag
  3164. ; Store edge data to RAM
  3165. mov Rcp_Edge_L, Temp1
  3166. mov Rcp_Edge_H, Temp2
  3167. ; Calculate pwm frequency
  3168. clr C
  3169. mov A, Temp1
  3170. subb A, Rcp_PrePrev_Edge_L
  3171. mov Temp1, A
  3172. mov A, Temp2
  3173. subb A, Rcp_PrePrev_Edge_H
  3174. mov Temp2, A
  3175. mov Temp4, #0
  3176. mov Temp7, #8 ; Set default period tolerance requirement (MSB)
  3177. mov Temp3, #0 ; (LSB)
  3178. ; Check if pulse is too short
  3179. clr C
  3180. mov A, Temp1
  3181. subb A, #low(140) ; If pulse below 70us, not accepted
  3182. mov A, Temp2
  3183. subb A, #high(140)
  3184. jnc pca_int_check_12kHz
  3185. mov Rcp_Period_Diff_Accepted, #0 ; Set not accepted
  3186. ajmp pca_int_store_data
  3187. pca_int_check_12kHz:
  3188. mov Bit_Access_Int, Temp1
  3189. mov Temp1, #Pgm_Enable_PWM_Input ; Check if PWM input is enabled
  3190. mov A, @Temp1
  3191. mov Temp1, Bit_Access_Int
  3192. jz pca_int_restore_edge ; If it is not - branch
  3193. ; Check if pwm frequency is 12kHz
  3194. clr C
  3195. mov A, Temp1
  3196. subb A, #low(200) ; If below 100us, 12kHz pwm is assumed
  3197. mov A, Temp2
  3198. subb A, #high(200)
  3199. jnc pca_int_check_8kHz
  3200. clr A
  3201. setb ACC.RCP_PWM_FREQ_12KHZ
  3202. mov Temp4, A
  3203. mov Temp3, #10 ; Set period tolerance requirement (LSB)
  3204. ajmp pca_int_restore_edge_set_msb
  3205. pca_int_check_8kHz:
  3206. ; Check if pwm frequency is 8kHz
  3207. clr C
  3208. mov A, Temp1
  3209. subb A, #low(360) ; If below 180us, 8kHz pwm is assumed
  3210. mov A, Temp2
  3211. subb A, #high(360)
  3212. jnc pca_int_check_4kHz
  3213. clr A
  3214. setb ACC.RCP_PWM_FREQ_8KHZ
  3215. mov Temp4, A
  3216. mov Temp3, #15 ; Set period tolerance requirement (LSB)
  3217. ajmp pca_int_restore_edge_set_msb
  3218. pca_int_check_4kHz:
  3219. ; Check if pwm frequency is 4kHz
  3220. clr C
  3221. mov A, Temp1
  3222. subb A, #low(720) ; If below 360us, 4kHz pwm is assumed
  3223. mov A, Temp2
  3224. subb A, #high(720)
  3225. jnc pca_int_check_2kHz
  3226. clr A
  3227. setb ACC.RCP_PWM_FREQ_4KHZ
  3228. mov Temp4, A
  3229. mov Temp3, #30 ; Set period tolerance requirement (LSB)
  3230. ajmp pca_int_restore_edge_set_msb
  3231. pca_int_check_2kHz:
  3232. ; Check if pwm frequency is 2kHz
  3233. clr C
  3234. mov A, Temp1
  3235. subb A, #low(1440) ; If below 720us, 2kHz pwm is assumed
  3236. mov A, Temp2
  3237. subb A, #high(1440)
  3238. jnc pca_int_check_1kHz
  3239. clr A
  3240. setb ACC.RCP_PWM_FREQ_2KHZ
  3241. mov Temp4, A
  3242. mov Temp3, #60 ; Set period tolerance requirement (LSB)
  3243. ajmp pca_int_restore_edge_set_msb
  3244. pca_int_check_1kHz:
  3245. ; Check if pwm frequency is 1kHz
  3246. clr C
  3247. mov A, Temp1
  3248. subb A, #low(2200) ; If below 1100us, 1kHz pwm is assumed
  3249. mov A, Temp2
  3250. subb A, #high(2200)
  3251. jnc pca_int_restore_edge
  3252. clr A
  3253. setb ACC.RCP_PWM_FREQ_1KHZ
  3254. mov Temp4, A
  3255. mov Temp3, #120 ; Set period tolerance requirement (LSB)
  3256. pca_int_restore_edge_set_msb:
  3257. mov Temp7, #0 ; Set period tolerance requirement (MSB)
  3258. pca_int_restore_edge:
  3259. ; Calculate difference between this period and previous period
  3260. clr C
  3261. mov A, Temp1
  3262. subb A, Rcp_Prev_Period_L
  3263. mov Temp5, A
  3264. mov A, Temp2
  3265. subb A, Rcp_Prev_Period_H
  3266. mov Temp6, A
  3267. ; Make positive
  3268. jnb ACC.7, pca_int_check_diff
  3269. mov A, Temp5
  3270. cpl A
  3271. add A, #1
  3272. mov Temp5, A
  3273. mov A, Temp6
  3274. cpl A
  3275. addc A, #0
  3276. mov Temp6, A
  3277. pca_int_check_diff:
  3278. ; Check difference
  3279. mov Rcp_Period_Diff_Accepted, #0 ; Set not accepted as default
  3280. clr C
  3281. mov A, Temp5
  3282. subb A, Temp3 ; Check difference
  3283. mov A, Temp6
  3284. subb A, Temp7
  3285. jnc pca_int_store_data
  3286. mov Rcp_Period_Diff_Accepted, #1 ; Set accepted
  3287. pca_int_store_data:
  3288. ; Store previous period
  3289. mov Rcp_Prev_Period_L, Temp1
  3290. mov Rcp_Prev_Period_H, Temp2
  3291. ; Store pre previous edge
  3292. mov Rcp_PrePrev_Edge_L, Rcp_Edge_L
  3293. mov Rcp_PrePrev_Edge_H, Rcp_Edge_H
  3294. mov Temp1, #RCP_VALIDATE
  3295. ajmp pca_int_limited
  3296. pca_int_fall:
  3297. ; RC pulse edge was second, calculate new pulse length
  3298. clr C
  3299. mov A, Temp1
  3300. subb A, Rcp_Prev_Edge_L
  3301. mov Temp1, A
  3302. mov A, Temp2
  3303. subb A, Rcp_Prev_Edge_H
  3304. mov Temp2, A
  3305. jnb Flags3.RCP_PWM_FREQ_12KHZ, ($+5) ; Is RC input pwm frequency 12kHz?
  3306. ajmp pca_int_pwm_divide_done ; Yes - branch forward
  3307. jnb Flags3.RCP_PWM_FREQ_8KHZ, ($+5) ; Is RC input pwm frequency 8kHz?
  3308. ajmp pca_int_pwm_divide_done ; Yes - branch forward
  3309. jnb Flags3.RCP_PWM_FREQ_4KHZ, ($+5) ; Is RC input pwm frequency 4kHz?
  3310. ajmp pca_int_pwm_divide ; Yes - branch forward
  3311. jb Flags2.RCP_PPM_ONESHOT125, ($+5)
  3312. ajmp pca_int_fall_not_oneshot
  3313. mov A, Temp2 ; Oneshot125 - move to I_Temp5/6
  3314. mov Temp6, A
  3315. mov A, Temp1
  3316. mov Temp5, A
  3317. ajmp pca_int_fall_check_range
  3318. pca_int_fall_not_oneshot:
  3319. mov A, Temp2 ; No - 2kHz. Divide by 2
  3320. clr C
  3321. rrc A
  3322. mov Temp2, A
  3323. mov A, Temp1
  3324. rrc A
  3325. mov Temp1, A
  3326. jnb Flags3.RCP_PWM_FREQ_2KHZ, ($+5) ; Is RC input pwm frequency 2kHz?
  3327. ajmp pca_int_pwm_divide ; Yes - branch forward
  3328. mov A, Temp2 ; No - 1kHz. Divide by 2 again
  3329. clr C
  3330. rrc A
  3331. mov Temp2, A
  3332. mov A, Temp1
  3333. rrc A
  3334. mov Temp1, A
  3335. jnb Flags3.RCP_PWM_FREQ_1KHZ, ($+5) ; Is RC input pwm frequency 1kHz?
  3336. ajmp pca_int_pwm_divide ; Yes - branch forward
  3337. mov A, Temp2 ; No - PPM. Divide by 2 (to bring range to 256) and move to Temp5/6
  3338. clr C
  3339. rrc A
  3340. mov Temp6, A
  3341. mov A, Temp1
  3342. rrc A
  3343. mov Temp5, A
  3344. pca_int_fall_check_range:
  3345. ; Skip range limitation if pwm frequency measurement
  3346. jb Flags0.RCP_MEAS_PWM_FREQ, pca_int_ppm_check_full_range
  3347. ; Check if 2160us or above (in order to ignore false pulses)
  3348. clr C
  3349. mov A, Temp5 ; Is pulse 2160us or higher?
  3350. subb A, #28
  3351. mov A, Temp6
  3352. subb A, #2
  3353. jc ($+4) ; No - proceed
  3354. ajmp pca_int_ppm_outside_range ; Yes - ignore pulse
  3355. pca_int_ppm_below_full_range:
  3356. ; Check if below 800us (in order to ignore false pulses)
  3357. mov A, Temp6
  3358. jnz pca_int_ppm_check_full_range
  3359. clr C
  3360. mov A, Temp5 ; Is pulse below 800us?
  3361. subb A, #200
  3362. jnc pca_int_ppm_check_full_range ; No - proceed
  3363. pca_int_ppm_outside_range:
  3364. inc Rcp_Outside_Range_Cnt
  3365. mov A, Rcp_Outside_Range_Cnt
  3366. jnz ($+4)
  3367. dec Rcp_Outside_Range_Cnt
  3368. clr C
  3369. mov A, Rcp_Outside_Range_Cnt
  3370. subb A, #10 ; Allow a given number of outside pulses
  3371. jnc ($+4)
  3372. ajmp pca_int_set_timeout ; If below limit - ignore pulse
  3373. mov New_Rcp, #0 ; Set pulse length to zero
  3374. setb Flags2.RCP_UPDATED ; Set updated flag
  3375. ajmp pca_int_set_timeout
  3376. pca_int_ppm_check_full_range:
  3377. ; Decrement outside range counter
  3378. mov A, Rcp_Outside_Range_Cnt
  3379. jz ($+4)
  3380. dec Rcp_Outside_Range_Cnt
  3381. ; Calculate "1000us" plus throttle minimum
  3382. IF MODE >= 1 ; Tail or multi
  3383. mov Temp1, #Pgm_Direction ; Check if bidirectional operation (store in Temp2)
  3384. mov A, @Temp1
  3385. mov Temp2, A
  3386. ENDIF
  3387. mov A, #0 ; Set 1000us as default minimum
  3388. jb Flags3.FULL_THROTTLE_RANGE, pca_int_ppm_calculate ; Check if full range is chosen
  3389. mov Temp1, #Pgm_Ppm_Min_Throttle ; Min throttle value is in 4us units
  3390. IF MODE >= 1 ; Tail or multi
  3391. cjne Temp2, #3, ($+5)
  3392. mov Temp1, #Pgm_Ppm_Center_Throttle ; Center throttle value is in 4us units
  3393. ENDIF
  3394. mov A, @Temp1
  3395. pca_int_ppm_calculate:
  3396. add A, #250 ; Add 1000us to minimum
  3397. mov Temp7, A
  3398. clr A
  3399. addc A, #0
  3400. mov Temp8, A
  3401. clr C
  3402. mov A, Temp5 ; Subtract minimum
  3403. subb A, Temp7
  3404. mov Temp5, A
  3405. mov A, Temp6
  3406. subb A, Temp8
  3407. mov Temp6, A
  3408. IF MODE >= 1 ; Tail or multi
  3409. mov Bit_Access_Int.0, C
  3410. cjne Temp2, #3, pca_int_ppm_bidir_dir_set; If not bidirectional operation - branch
  3411. mov C, Bit_Access_Int.0
  3412. jnc pca_int_ppm_bidir_fwd ; If result is positive - branch
  3413. jb Flags2.RCP_DIR_REV, pca_int_ppm_bidir_dir_set ; If same direction - branch
  3414. setb Flags2.RCP_DIR_REV
  3415. ajmp pca_int_ppm_bidir_dir_set
  3416. pca_int_ppm_bidir_fwd:
  3417. jnb Flags2.RCP_DIR_REV, pca_int_ppm_bidir_dir_set ; If same direction - branch
  3418. clr Flags2.RCP_DIR_REV
  3419. pca_int_ppm_bidir_dir_set:
  3420. mov C, Bit_Access_Int.0
  3421. ENDIF
  3422. jnc pca_int_ppm_neg_checked ; If result is positive - branch
  3423. IF MODE >= 1 ; Tail or multi
  3424. cjne Temp2, #3, pca_int_ppm_unidir_neg ; If not bidirectional operation - branch
  3425. mov A, Temp5 ; Change sign
  3426. cpl A
  3427. add A, #1
  3428. mov Temp5, A
  3429. mov A, Temp6
  3430. cpl A
  3431. addc A, #0
  3432. mov Temp6, A
  3433. jmp pca_int_ppm_neg_checked
  3434. pca_int_ppm_unidir_neg:
  3435. ENDIF
  3436. mov Temp1, #RCP_MIN ; Yes - set to minimum
  3437. mov Temp2, #0
  3438. ajmp pca_int_pwm_divide_done
  3439. pca_int_ppm_neg_checked:
  3440. IF MODE >= 1 ; Tail or multi
  3441. cjne Temp2, #3, pca_int_ppm_bidir_done ; If not bidirectional operation - branch
  3442. mov A, Temp5 ; Multiply value by 2
  3443. rlc A
  3444. mov Temp5, A
  3445. mov A, Temp6
  3446. rlc A
  3447. mov Temp6, A
  3448. clr C ; Subtract deadband
  3449. mov A, Temp5
  3450. subb A, #10
  3451. mov Temp5, A
  3452. mov A, Temp6
  3453. subb A, #0
  3454. mov Temp6, A
  3455. jnc pca_int_ppm_bidir_done
  3456. mov Temp5, #RCP_MIN
  3457. mov Temp6, #0
  3458. pca_int_ppm_bidir_done:
  3459. ENDIF
  3460. clr C ; Check that RC pulse is within legal range (max 255)
  3461. mov A, Temp5
  3462. subb A, #RCP_MAX
  3463. mov A, Temp6
  3464. subb A, #0
  3465. jc pca_int_ppm_max_checked
  3466. mov Temp1, #RCP_MAX
  3467. mov Temp2, #0
  3468. ajmp pca_int_pwm_divide_done
  3469. pca_int_ppm_max_checked:
  3470. mov A, Temp5 ; Multiply throttle value by gain
  3471. mov B, Ppm_Throttle_Gain
  3472. mul AB
  3473. xch A, B
  3474. mov C, B.7 ; Multiply result by 2 (unity gain is 128)
  3475. rlc A
  3476. mov Temp1, A ; Transfer to Temp1/2
  3477. mov Temp2, #0
  3478. jc pca_int_ppm_limit_after_mult
  3479. jmp pca_int_limited
  3480. pca_int_ppm_limit_after_mult:
  3481. mov Temp1, #RCP_MAX
  3482. mov Temp2, #0
  3483. jmp pca_int_limited
  3484. pca_int_pwm_divide:
  3485. mov A, Temp2 ; Divide by 2
  3486. clr C
  3487. rrc A
  3488. mov Temp2, A
  3489. mov A, Temp1
  3490. rrc A
  3491. mov Temp1, A
  3492. pca_int_pwm_divide_done:
  3493. jnb Flags3.RCP_PWM_FREQ_12KHZ, pca_int_check_legal_range ; Is RC input pwm frequency 12kHz?
  3494. mov A, Temp2 ; Yes - check that value is not more than 255
  3495. jz ($+4)
  3496. mov Temp1, #RCP_MAX
  3497. clr C
  3498. mov A, Temp1 ; Multiply by 1.5
  3499. rrc A
  3500. addc A, Temp1
  3501. mov Temp1, A
  3502. clr A
  3503. addc A, #0
  3504. mov Temp2, A
  3505. pca_int_check_legal_range:
  3506. ; Check that RC pulse is within legal range
  3507. clr C
  3508. mov A, Temp1
  3509. subb A, #RCP_MAX
  3510. mov A, Temp2
  3511. subb A, #0
  3512. jc pca_int_limited
  3513. mov Temp1, #RCP_MAX
  3514. pca_int_limited:
  3515. ; RC pulse value accepted
  3516. mov New_Rcp, Temp1 ; Store new pulse length
  3517. setb Flags2.RCP_UPDATED ; Set updated flag
  3518. jb Flags0.RCP_MEAS_PWM_FREQ, ($+5) ; Is measure RCP pwm frequency flag set?
  3519. ajmp pca_int_set_timeout ; No - skip measurements
  3520. 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))
  3521. cpl A
  3522. anl A, Flags3 ; Clear all pwm frequency flags
  3523. orl A, Temp4 ; Store pwm frequency value in flags
  3524. mov Flags3, A
  3525. clr Flags2.RCP_PPM ; Default, flag is not set (PWM)
  3526. mov A, Temp4 ; Check if all flags are cleared
  3527. jnz pca_int_set_timeout
  3528. setb Flags2.RCP_PPM ; Set flag (PPM)
  3529. pca_int_set_timeout:
  3530. mov Rcp_Timeout_Cntd, #RCP_TIMEOUT ; Set timeout count to start value
  3531. jnb Flags2.RCP_PPM, pca_int_ppm_timeout_set ; If flag is not set (PWM) - branch
  3532. mov Rcp_Timeout_Cntd, #RCP_TIMEOUT_PPM ; No flag set means PPM. Set timeout count
  3533. pca_int_ppm_timeout_set:
  3534. jnb Flags0.RCP_MEAS_PWM_FREQ, ($+5) ; Is measure RCP pwm frequency flag set?
  3535. ajmp pca_int_exit ; Yes - exit
  3536. jb Flags2.RCP_PPM, pca_int_exit ; If flag is set (PPM) - branch
  3537. Rcp_Int_Disable ; Disable RC pulse interrupt
  3538. pca_int_exit: ; Exit interrupt routine
  3539. jb Flags2.RCP_PPM, ($+6) ; If flag is set (PPP) - branch
  3540. mov Rcp_Skip_Cntd, #RCP_SKIP_RATE ; Load number of skips
  3541. pop B ; Restore preserved registers
  3542. pop ACC
  3543. pop PSW
  3544. setb ET2 ; Enable timer2 interrupts
  3545. orl EIE1, #10h ; Enable PCA0 interrupts
  3546. reti
  3547. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  3548. ;
  3549. ; Wait xms ~(x*4*250) (Different entry points)
  3550. ;
  3551. ; No assumptions
  3552. ;
  3553. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  3554. wait1ms:
  3555. mov Temp2, #1
  3556. jmp waitxms_o
  3557. wait3ms:
  3558. mov Temp2, #3
  3559. jmp waitxms_o
  3560. wait10ms:
  3561. mov Temp2, #10
  3562. jmp waitxms_o
  3563. wait30ms:
  3564. mov Temp2, #30
  3565. jmp waitxms_o
  3566. wait100ms:
  3567. mov Temp2, #100
  3568. jmp waitxms_o
  3569. wait200ms:
  3570. mov Temp2, #200
  3571. jmp waitxms_o
  3572. waitxms_o: ; Outer loop
  3573. mov Temp1, #23
  3574. waitxms_m: ; Middle loop
  3575. clr A
  3576. djnz ACC, $ ; Inner loop (42.7us - 1024 cycles)
  3577. djnz Temp1, waitxms_m
  3578. djnz Temp2, waitxms_o
  3579. ret
  3580. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  3581. ;
  3582. ; Beeper routines (4 different entry points)
  3583. ;
  3584. ; No assumptions
  3585. ;
  3586. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  3587. beep_f1: ; Entry point 1, load beeper frequency 1 settings
  3588. mov Temp3, #20 ; Off wait loop length
  3589. mov Temp4, #120 ; Number of beep pulses
  3590. jmp beep
  3591. beep_f2: ; Entry point 2, load beeper frequency 2 settings
  3592. mov Temp3, #16
  3593. mov Temp4, #140
  3594. jmp beep
  3595. beep_f3: ; Entry point 3, load beeper frequency 3 settings
  3596. mov Temp3, #13
  3597. mov Temp4, #180
  3598. jmp beep
  3599. beep_f4: ; Entry point 4, load beeper frequency 4 settings
  3600. mov Temp3, #11
  3601. mov Temp4, #200
  3602. jmp beep
  3603. beep: ; Beep loop start
  3604. mov A, Beep_Strength
  3605. djnz ACC, beep_start
  3606. ret
  3607. beep_start:
  3608. mov Temp2, #2
  3609. beep_onoff:
  3610. clr A
  3611. BpFET_off ; BpFET off
  3612. djnz ACC, $ ; Allow some time after pfet is turned off
  3613. BnFET_on ; BnFET on (in order to charge the driver of the BpFET)
  3614. djnz ACC, $ ; Let the nfet be turned on a while
  3615. BnFET_off ; BnFET off again
  3616. djnz ACC, $ ; Allow some time after nfet is turned off
  3617. BpFET_on ; BpFET on
  3618. djnz ACC, $ ; Allow some time after pfet is turned on
  3619. ; Turn on nfet
  3620. mov A, Temp2
  3621. jb ACC.0, beep_anfet_on
  3622. AnFET_on ; AnFET on
  3623. beep_anfet_on:
  3624. jnb ACC.0, beep_cnfet_on
  3625. CnFET_on ; CnFET on
  3626. beep_cnfet_on:
  3627. mov A, Beep_Strength
  3628. djnz ACC, $
  3629. ; Turn off nfet
  3630. mov A, Temp2
  3631. jb ACC.0, beep_anfet_off
  3632. AnFET_off ; AnFET off
  3633. beep_anfet_off:
  3634. jnb ACC.0, beep_cnfet_off
  3635. CnFET_off ; CnFET off
  3636. beep_cnfet_off:
  3637. mov A, #150 ; 25�s off
  3638. djnz ACC, $
  3639. djnz Temp2, beep_onoff
  3640. ; Copy variable
  3641. mov A, Temp3
  3642. mov Temp1, A
  3643. beep_off: ; Fets off loop
  3644. djnz ACC, $
  3645. djnz Temp1, beep_off
  3646. djnz Temp4, beep
  3647. BpFET_off ; BpFET off
  3648. ret
  3649. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  3650. ;
  3651. ; Division 16bit unsigned by 16bit unsigned
  3652. ;
  3653. ; Dividend shall be in Temp2/Temp1, divisor in Temp4/Temp3
  3654. ; Result will be in Temp2/Temp1
  3655. ;
  3656. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  3657. div_u16_by_u16:
  3658. clr C
  3659. mov Temp5, #0
  3660. mov Temp6, #0
  3661. mov B, #0
  3662. div_u16_by_u16_div1:
  3663. inc B ; Increment counter for each left shift
  3664. mov A, Temp3 ; Shift left the divisor
  3665. rlc A
  3666. mov Temp3, A
  3667. mov A, Temp4
  3668. rlc A
  3669. mov Temp4, A
  3670. jnc div_u16_by_u16_div1 ; Repeat until carry flag is set from high-byte
  3671. div_u16_by_u16_div2:
  3672. mov A, Temp4 ; Shift right the divisor
  3673. rrc A
  3674. mov Temp4, A
  3675. mov A, Temp3
  3676. rrc A
  3677. mov Temp3, A
  3678. clr C
  3679. mov A, Temp2 ; Make a safe copy of the dividend
  3680. mov Temp8, A
  3681. mov A, Temp1
  3682. mov Temp7, A
  3683. mov A, Temp1 ; Move low-byte of dividend into accumulator
  3684. subb A, Temp3 ; Dividend - shifted divisor = result bit (no factor, only 0 or 1)
  3685. mov Temp1, A ; Save updated dividend
  3686. mov A, Temp2 ; Move high-byte of dividend into accumulator
  3687. subb A, Temp4 ; Subtract high-byte of divisor (all together 16-bit substraction)
  3688. mov Temp2, A ; Save updated high-byte back in high-byte of divisor
  3689. jnc div_u16_by_u16_div3 ; If carry flag is NOT set, result is 1
  3690. mov A, Temp8 ; Otherwise result is 0, save copy of divisor to undo subtraction
  3691. mov Temp2, A
  3692. mov A, Temp7
  3693. mov Temp1, A
  3694. div_u16_by_u16_div3:
  3695. cpl C ; Invert carry, so it can be directly copied into result
  3696. mov A, Temp5
  3697. rlc A ; Shift carry flag into temporary result
  3698. mov Temp5, A
  3699. mov A, Temp6
  3700. rlc A
  3701. mov Temp6,A
  3702. djnz B, div_u16_by_u16_div2 ;Now count backwards and repeat until "B" is zero
  3703. mov A, Temp6 ; Move result to Temp2/Temp1
  3704. mov Temp2, A
  3705. mov A, Temp5
  3706. mov Temp1, A
  3707. ret
  3708. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  3709. ;
  3710. ; Multiplication 16bit signed by 8bit unsigned
  3711. ;
  3712. ; Multiplicand shall be in Temp2/Temp1, multiplicator in Temp3
  3713. ; Result will be in Temp2/Temp1. Result will divided by 16
  3714. ;
  3715. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  3716. mult_s16_by_u8_div_16:
  3717. mov A, Temp1 ; Read input to math registers
  3718. mov B, Temp2
  3719. mov Bit_Access, Temp3
  3720. setb PSW.4 ; Select register bank 2 for math routines
  3721. mov Temp1, A ; Store in math registers
  3722. mov Temp2, B
  3723. mov Temp4, #0 ; Set sign in Temp4 and test sign
  3724. jnb B.7, mult_s16_by_u8_positive
  3725. mov Temp4, #0FFh
  3726. cpl A
  3727. add A, #1
  3728. mov Temp1, A
  3729. mov A, Temp2
  3730. cpl A
  3731. addc A, #0
  3732. mov Temp2, A
  3733. mult_s16_by_u8_positive:
  3734. mov A, Temp1 ; Multiply LSB with multiplicator
  3735. mov B, Bit_Access
  3736. mul AB
  3737. mov Temp6, B ; Place MSB in Temp6
  3738. mov Temp1, A ; Place LSB in Temp1 (result)
  3739. mov A, Temp2 ; Multiply MSB with multiplicator
  3740. mov B, Bit_Access
  3741. mul AB
  3742. mov Temp8, B ; Place in Temp8/7
  3743. mov Temp7, A
  3744. mov A, Temp6 ; Add up
  3745. add A, Temp7
  3746. mov Temp2, A
  3747. mov A, #0
  3748. addc A, Temp8
  3749. mov Temp3, A
  3750. mov Temp5, #4 ; Set number of divisions
  3751. mult_s16_by_u8_div_loop:
  3752. clr C ; Rotate right
  3753. mov A, Temp3
  3754. rrc A
  3755. mov Temp3, A
  3756. mov A, Temp2
  3757. rrc A
  3758. mov Temp2, A
  3759. mov A, Temp1
  3760. rrc A
  3761. mov Temp1, A
  3762. djnz Temp5, mult_s16_by_u8_div_loop
  3763. mov B, Temp4 ; Test sign
  3764. jnb B.7, mult_s16_by_u8_exit
  3765. mov A, Temp1
  3766. cpl A
  3767. add A, #1
  3768. mov Temp1, A
  3769. mov A, Temp2
  3770. cpl A
  3771. addc A, #0
  3772. mov Temp2, A
  3773. mult_s16_by_u8_exit:
  3774. mov A, Temp1 ; Store output
  3775. mov B, Temp2
  3776. clr PSW.4 ; Select normal register bank
  3777. mov Temp1, A
  3778. mov Temp2, B
  3779. ret
  3780. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  3781. ;
  3782. ; Calculate governor routines
  3783. ;
  3784. ; No assumptions
  3785. ;
  3786. ; Governs headspeed based upon the Comm_Period4x variable and pwm
  3787. ; The governor task is split into several routines in order to distribute processing time
  3788. ;
  3789. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  3790. ; First governor routine - calculate governor target
  3791. IF MODE == 0 ; Main
  3792. calc_governor_target:
  3793. mov Temp1, #Pgm_Gov_Mode ; Governor mode?
  3794. cjne @Temp1, #4, governor_speed_check ; Yes
  3795. jmp calc_governor_target_exit ; No
  3796. governor_speed_check:
  3797. ; Stop governor for stop RC pulse
  3798. clr C
  3799. mov A, New_Rcp ; Check RC pulse against stop value
  3800. subb A, #(RCP_MAX/10) ; Is pulse below stop value?
  3801. jc governor_deactivate ; Yes - deactivate
  3802. mov A, Flags1
  3803. anl A, #((1 SHL STARTUP_PHASE)+(1 SHL INITIAL_RUN_PHASE))
  3804. jnz governor_deactivate ; Deactivate if any startup phase set
  3805. ; Skip speed check if governor is already active
  3806. jb Flags1.GOV_ACTIVE, governor_target_calc
  3807. ; Check speed (do not run governor for low speeds)
  3808. mov Temp1, #05h ; Default high range activation limit value (~62500 eRPM)
  3809. mov Temp2, #Pgm_Gov_Range
  3810. mov A, @Temp2 ; Check if high range (Temp2 has #Pgm_Gov_Range)
  3811. dec A
  3812. jz governor_act_lim_set ; If high range - branch
  3813. mov Temp1, #0Ah ; Middle range activation limit value (~31250 eRPM)
  3814. dec A
  3815. jz governor_act_lim_set ; If middle range - branch
  3816. mov Temp1, #12h ; Low range activation limit value (~17400 eRPM)
  3817. governor_act_lim_set:
  3818. clr C
  3819. mov A, Comm_Period4x_H
  3820. subb A, Temp1
  3821. jc governor_activate ; If speed above min limit - run governor
  3822. governor_deactivate:
  3823. jnb Flags1.GOV_ACTIVE, governor_first_deactivate_done; This code is executed continuously. Only execute the code below the first time
  3824. mov Pwm_Limit_Spoolup, Pwm_Spoolup_Beg
  3825. mov Spoolup_Limit_Cnt, #255
  3826. mov Spoolup_Limit_Skip, #1
  3827. governor_first_deactivate_done:
  3828. mov Current_Pwm, Requested_Pwm ; Set current pwm to requested
  3829. clr A
  3830. mov Gov_Target_L, A ; Set target to zero
  3831. mov Gov_Target_H, A
  3832. mov Gov_Integral_L, A ; Set integral to zero
  3833. mov Gov_Integral_H, A
  3834. mov Gov_Integral_X, A
  3835. clr Flags1.GOV_ACTIVE
  3836. jmp calc_governor_target_exit
  3837. governor_activate:
  3838. setb Flags1.GOV_ACTIVE
  3839. governor_target_calc:
  3840. ; Governor calculations
  3841. mov Temp2, #Pgm_Gov_Range
  3842. mov A, @Temp2 ; Check high, middle or low range
  3843. dec A
  3844. jnz calc_governor_target_middle
  3845. mov A, Governor_Req_Pwm ; Load governor requested pwm
  3846. cpl A ; Calculate 255-pwm (invert pwm)
  3847. ; Calculate comm period target (1 + 2*((255-Requested_Pwm)/256) - 0.25)
  3848. rlc A ; Msb to carry
  3849. rlc A ; To bit0
  3850. mov Temp2, A ; Now 1 lsb is valid for H
  3851. rrc A
  3852. mov Temp1, A ; Now 7 msbs are valid for L
  3853. mov A, Temp2
  3854. anl A, #01h ; Calculate H byte
  3855. inc A ; Add 1
  3856. mov Temp2, A
  3857. mov A, Temp1
  3858. anl A, #0FEh ; Calculate L byte
  3859. jmp calc_governor_subtract_025
  3860. calc_governor_target_middle:
  3861. mov A, @Temp2 ; Check middle or low range (Temp2 has #Pgm_Gov_Range)
  3862. dec A
  3863. dec A
  3864. jnz calc_governor_target_low
  3865. mov A, Governor_Req_Pwm ; Load governor requested pwm
  3866. cpl A ; Calculate 255-pwm (invert pwm)
  3867. ; Calculate comm period target (1 + 4*((255-Requested_Pwm)/256))
  3868. rlc A ; Msb to carry
  3869. rlc A ; To bit0
  3870. rlc A ; To bit1
  3871. mov Temp2, A ; Now 2 lsbs are valid for H
  3872. rrc A
  3873. mov Temp1, A ; Now 6 msbs are valid for L
  3874. mov A, Temp2
  3875. anl A, #03h ; Calculate H byte
  3876. inc A ; Add 1
  3877. mov Temp2, A
  3878. mov A, Temp1
  3879. anl A, #0FCh ; Calculate L byte
  3880. jmp calc_governor_store_target
  3881. calc_governor_target_low:
  3882. mov A, Governor_Req_Pwm ; Load governor requested pwm
  3883. cpl A ; Calculate 255-pwm (invert pwm)
  3884. ; Calculate comm period target (2 + 8*((255-Requested_Pwm)/256) - 0.25)
  3885. rlc A ; Msb to carry
  3886. rlc A ; To bit0
  3887. rlc A ; To bit1
  3888. rlc A ; To bit2
  3889. mov Temp2, A ; Now 3 lsbs are valid for H
  3890. rrc A
  3891. mov Temp1, A ; Now 5 msbs are valid for L
  3892. mov A, Temp2
  3893. anl A, #07h ; Calculate H byte
  3894. inc A ; Add 1
  3895. inc A ; Add 1 more
  3896. mov Temp2, A
  3897. mov A, Temp1
  3898. anl A, #0F8h ; Calculate L byte
  3899. calc_governor_subtract_025:
  3900. clr C
  3901. subb A, #40h ; Subtract 0.25
  3902. mov Temp1, A
  3903. mov A, Temp2
  3904. subb A, #0
  3905. mov Temp2, A
  3906. calc_governor_store_target:
  3907. ; Store governor target
  3908. mov Gov_Target_L, Temp1
  3909. mov Gov_Target_H, Temp2
  3910. calc_governor_target_exit:
  3911. ret
  3912. ENDIF
  3913. IF MODE == 1 ; Tail
  3914. calc_governor_target:
  3915. ret
  3916. ENDIF
  3917. IF MODE == 2 ; Multi
  3918. calc_governor_target:
  3919. mov Temp1, #Pgm_Gov_Mode ; Closed loop mode?
  3920. cjne @Temp1, #4, governor_target_calc ; Yes - branch
  3921. jmp calc_governor_target_exit ; No
  3922. governor_target_calc:
  3923. ; Stop governor for stop RC pulse
  3924. clr C
  3925. mov A, New_Rcp ; Check RC pulse against stop value
  3926. subb A, #RCP_STOP ; Is pulse below stop value?
  3927. jc governor_deactivate ; Yes - deactivate
  3928. jmp governor_activate ; No - activate
  3929. governor_deactivate:
  3930. mov Current_Pwm, Requested_Pwm ; Set current pwm to requested
  3931. clr A
  3932. mov Gov_Target_L, A ; Set target to zero
  3933. mov Gov_Target_H, A
  3934. mov Gov_Integral_L, A ; Set integral to zero
  3935. mov Gov_Integral_H, A
  3936. mov Gov_Integral_X, A
  3937. clr Flags1.GOV_ACTIVE
  3938. jmp calc_governor_target_exit
  3939. governor_activate:
  3940. mov Temp1, #Pgm_Gov_Mode ; Store gov mode
  3941. mov A, @Temp1
  3942. mov Temp5, A
  3943. setb Flags1.GOV_ACTIVE
  3944. mov A, Requested_Pwm ; Load requested pwm
  3945. mov Governor_Req_Pwm, A ; Set governor requested pwm
  3946. ; Calculate comm period target 2*(51000/Requested_Pwm)
  3947. mov Temp1, #38h ; Load 51000
  3948. mov Temp2, #0C7h
  3949. mov Temp3, Comm_Period4x_L ; Load comm period
  3950. mov Temp4, Comm_Period4x_H
  3951. ; Set speed range
  3952. clr C
  3953. mov A, Temp4
  3954. rrc A
  3955. mov Temp4, A
  3956. mov A, Temp3
  3957. rrc A
  3958. mov Temp3, A ; 200k eRPM range here
  3959. ; Check range
  3960. mov A, Temp5
  3961. dec A
  3962. jz governor_activate_range_set ; 200k eRPM? - branch
  3963. governor_activate_100k:
  3964. clr C
  3965. mov A, Temp4
  3966. rrc A
  3967. mov Temp4, A
  3968. mov A, Temp3
  3969. rrc A
  3970. mov Temp3, A ; 100k eRPM range here
  3971. mov A, Temp5 ; Check range again
  3972. dec A
  3973. dec A
  3974. jz governor_activate_range_set ; 100k eRPM? - branch
  3975. governor_activate_50k:
  3976. clr C
  3977. mov A, Temp4
  3978. rrc A
  3979. mov Temp4, A
  3980. mov A, Temp3
  3981. rrc A
  3982. mov Temp3, A ; 50k eRPM range here
  3983. governor_activate_range_set:
  3984. call div_u16_by_u16
  3985. ; Store governor target
  3986. mov Gov_Target_L, Temp1
  3987. mov Gov_Target_H, Temp2
  3988. calc_governor_target_exit:
  3989. ret
  3990. ENDIF
  3991. ; Second governor routine - calculate governor proportional error
  3992. calc_governor_prop_error:
  3993. IF MODE <= 1 ; Main or tail
  3994. ; Load comm period and divide by 2
  3995. clr C
  3996. mov A, Comm_Period4x_H
  3997. rrc A
  3998. mov Temp2, A
  3999. mov A, Comm_Period4x_L
  4000. rrc A
  4001. mov Temp1, A
  4002. ; Calculate error
  4003. clr C
  4004. mov A, Gov_Target_L
  4005. subb A, Temp1
  4006. mov Temp1, A
  4007. mov A, Gov_Target_H
  4008. subb A, Temp2
  4009. mov Temp2, A
  4010. ENDIF
  4011. IF MODE == 2 ; Multi
  4012. ; Calculate error
  4013. clr C
  4014. mov A, Gov_Target_L
  4015. subb A, Governor_Req_Pwm
  4016. mov Temp1, A
  4017. mov A, Gov_Target_H
  4018. subb A, #0
  4019. mov Temp2, A
  4020. ENDIF
  4021. ; Check error and limit
  4022. jnc governor_check_prop_limit_pos ; Check carry
  4023. clr C
  4024. mov A, Temp1
  4025. subb A, #80h ; Is error too negative?
  4026. mov A, Temp2
  4027. subb A, #0FFh
  4028. jc governor_limit_prop_error_neg ; Yes - limit
  4029. jmp governor_store_prop_error
  4030. governor_check_prop_limit_pos:
  4031. clr C
  4032. mov A, Temp1
  4033. subb A, #7Fh ; Is error too positive?
  4034. mov A, Temp2
  4035. subb A, #00h
  4036. jnc governor_limit_prop_error_pos ; Yes - limit
  4037. jmp governor_store_prop_error
  4038. governor_limit_prop_error_pos:
  4039. mov Temp1, #7Fh ; Limit to max positive (2's complement)
  4040. mov Temp2, #00h
  4041. jmp governor_store_prop_error
  4042. governor_limit_prop_error_neg:
  4043. mov Temp1, #80h ; Limit to max negative (2's complement)
  4044. mov Temp2, #0FFh
  4045. governor_store_prop_error:
  4046. ; Store proportional
  4047. mov Gov_Proportional_L, Temp1
  4048. mov Gov_Proportional_H, Temp2
  4049. calc_governor_prop_error_exit:
  4050. ret
  4051. ; Third governor routine - calculate governor integral error
  4052. calc_governor_int_error:
  4053. ; Add proportional to integral
  4054. mov A, Gov_Proportional_L
  4055. add A, Gov_Integral_L
  4056. mov Temp1, A
  4057. mov A, Gov_Proportional_H
  4058. addc A, Gov_Integral_H
  4059. mov Temp2, A
  4060. mov Bit_Access, Gov_Proportional_H ; Sign extend high byte
  4061. clr A
  4062. jnb Bit_Access.7, ($+4)
  4063. cpl A
  4064. addc A, Gov_Integral_X
  4065. mov Temp3, A
  4066. ; Check integral and limit
  4067. jnb ACC.7, governor_check_int_limit_pos ; Check sign bit
  4068. clr C
  4069. mov A, Temp3
  4070. subb A, #0F0h ; Is error too negative?
  4071. jc governor_limit_int_error_neg ; Yes - limit
  4072. jmp governor_check_pwm
  4073. governor_check_int_limit_pos:
  4074. clr C
  4075. mov A, Temp3
  4076. subb A, #0Fh ; Is error too positive?
  4077. jnc governor_limit_int_error_pos ; Yes - limit
  4078. jmp governor_check_pwm
  4079. governor_limit_int_error_pos:
  4080. mov Temp1, #0FFh ; Limit to max positive (2's complement)
  4081. mov Temp2, #0FFh
  4082. mov Temp3, #0Fh
  4083. jmp governor_check_pwm
  4084. governor_limit_int_error_neg:
  4085. mov Temp1, #00h ; Limit to max negative (2's complement)
  4086. mov Temp2, #00h
  4087. mov Temp3, #0F0h
  4088. governor_check_pwm:
  4089. ; Check current pwm
  4090. clr C
  4091. mov A, Current_Pwm
  4092. subb A, Pwm_Limit ; Is current pwm at or above pwm limit?
  4093. jnc governor_int_max_pwm ; Yes - branch
  4094. clr C
  4095. mov A, #1
  4096. subb A, Current_Pwm ; Is current pwm at minimum?
  4097. jnc governor_int_min_pwm ; Yes - branch
  4098. jmp governor_store_int_error ; No - store integral error
  4099. governor_int_max_pwm:
  4100. mov A, Gov_Proportional_H
  4101. jb ACC.7, calc_governor_int_error_exit ; Is proportional error negative - branch (high byte is always zero)
  4102. jmp governor_store_int_error ; Positive - store integral error
  4103. governor_int_min_pwm:
  4104. mov A, Gov_Proportional_H
  4105. jnb ACC.7, calc_governor_int_error_exit ; Is proportional error positive - branch (high byte is always zero)
  4106. governor_store_int_error:
  4107. ; Store integral
  4108. mov Gov_Integral_L, Temp1
  4109. mov Gov_Integral_H, Temp2
  4110. mov Gov_Integral_X, Temp3
  4111. calc_governor_int_error_exit:
  4112. ret
  4113. ; Fourth governor routine - calculate governor proportional correction
  4114. calc_governor_prop_correction:
  4115. ; Load proportional gain
  4116. mov Temp1, #Pgm_Gov_P_Gain_Decoded; Load proportional gain
  4117. mov A, @Temp1
  4118. mov Temp3, A ; Store in Temp3
  4119. ; Load proportional
  4120. clr C
  4121. mov A, Gov_Proportional_L ; Nominal multiply by 2
  4122. rlc A
  4123. mov Temp1, A
  4124. mov A, Gov_Proportional_H
  4125. rlc A
  4126. mov Temp2, A
  4127. ; Apply gain
  4128. call mult_s16_by_u8_div_16
  4129. ; Check error and limit (to low byte)
  4130. mov A, Temp2
  4131. jnb ACC.7, governor_check_prop_corr_limit_pos ; Check sign bit
  4132. clr C
  4133. mov A, Temp1
  4134. subb A, #80h ; Is error too negative?
  4135. mov A, Temp2
  4136. subb A, #0FFh
  4137. jc governor_limit_prop_corr_neg ; Yes - limit
  4138. ajmp governor_apply_prop_corr
  4139. governor_check_prop_corr_limit_pos:
  4140. clr C
  4141. mov A, Temp1
  4142. subb A, #7Fh ; Is error too positive?
  4143. mov A, Temp2
  4144. subb A, #00h
  4145. jnc governor_limit_prop_corr_pos ; Yes - limit
  4146. ajmp governor_apply_prop_corr
  4147. governor_limit_prop_corr_pos:
  4148. mov Temp1, #7Fh ; Limit to max positive (2's complement)
  4149. mov Temp2, #00h
  4150. ajmp governor_apply_prop_corr
  4151. governor_limit_prop_corr_neg:
  4152. mov Temp1, #80h ; Limit to max negative (2's complement)
  4153. mov Temp2, #0FFh
  4154. governor_apply_prop_corr:
  4155. ; Test proportional sign
  4156. mov A, Temp1
  4157. jb ACC.7, governor_corr_neg_prop ; If proportional negative - go to correct negative
  4158. ; Subtract positive proportional
  4159. clr C
  4160. mov A, Governor_Req_Pwm
  4161. subb A, Temp1
  4162. mov Temp1, A
  4163. ; Check result
  4164. jc governor_corr_prop_min_pwm ; Is result negative?
  4165. clr C
  4166. mov A, Temp1 ; Is result below pwm min?
  4167. subb A, #1
  4168. jc governor_corr_prop_min_pwm ; Yes
  4169. jmp governor_store_prop_corr ; No - store proportional correction
  4170. governor_corr_prop_min_pwm:
  4171. mov Temp1, #1 ; Load minimum pwm
  4172. jmp governor_store_prop_corr
  4173. governor_corr_neg_prop:
  4174. ; Add negative proportional
  4175. mov A, Temp1
  4176. cpl A
  4177. add A, #1
  4178. add A, Governor_Req_Pwm
  4179. mov Temp1, A
  4180. ; Check result
  4181. jc governor_corr_prop_max_pwm ; Is result above max?
  4182. jmp governor_store_prop_corr ; No - store proportional correction
  4183. governor_corr_prop_max_pwm:
  4184. mov Temp1, #255 ; Load maximum pwm
  4185. governor_store_prop_corr:
  4186. ; Store proportional pwm
  4187. mov Gov_Prop_Pwm, Temp1
  4188. calc_governor_prop_corr_exit:
  4189. ret
  4190. ; Fifth governor routine - calculate governor integral correction
  4191. calc_governor_int_correction:
  4192. ; Load integral gain
  4193. mov Temp1, #Pgm_Gov_I_Gain_Decoded; Load integral gain
  4194. mov A, @Temp1
  4195. mov Temp3, A ; Store in Temp3
  4196. ; Load integral
  4197. mov Temp1, Gov_Integral_H
  4198. mov Temp2, Gov_Integral_X
  4199. ; Apply gain
  4200. call mult_s16_by_u8_div_16
  4201. ; Check integral and limit
  4202. mov A, Temp2
  4203. jnb ACC.7, governor_check_int_corr_limit_pos ; Check sign bit
  4204. clr C
  4205. mov A, Temp1
  4206. subb A, #01h ; Is integral too negative?
  4207. mov A, Temp2
  4208. subb A, #0FFh
  4209. jc governor_limit_int_corr_neg ; Yes - limit
  4210. jmp governor_apply_int_corr
  4211. governor_check_int_corr_limit_pos:
  4212. clr C
  4213. mov A, Temp1
  4214. subb A, #0FFh ; Is integral too positive?
  4215. mov A, Temp2
  4216. subb A, #00h
  4217. jnc governor_limit_int_corr_pos ; Yes - limit
  4218. jmp governor_apply_int_corr
  4219. governor_limit_int_corr_pos:
  4220. mov Temp1, #0FFh ; Limit to max positive (2's complement)
  4221. mov Temp2, #00h
  4222. jmp governor_apply_int_corr
  4223. governor_limit_int_corr_neg:
  4224. mov Temp1, #01h ; Limit to max negative (2's complement)
  4225. mov Temp2, #0FFh
  4226. governor_apply_int_corr:
  4227. ; Test integral sign
  4228. mov A, Temp2
  4229. jb ACC.7, governor_corr_neg_int ; If integral negative - go to correct negative
  4230. ; Subtract positive integral
  4231. clr C
  4232. mov A, Gov_Prop_Pwm
  4233. subb A, Temp1
  4234. mov Temp1, A
  4235. ; Check result
  4236. jc governor_corr_int_min_pwm ; Is result negative?
  4237. clr C
  4238. mov A, Temp1 ; Is result below pwm min?
  4239. subb A, #1
  4240. jc governor_corr_int_min_pwm ; Yes
  4241. jmp governor_store_int_corr ; No - store correction
  4242. governor_corr_int_min_pwm:
  4243. mov Temp1, #1 ; Load minimum pwm
  4244. jmp governor_store_int_corr
  4245. governor_corr_neg_int:
  4246. ; Add negative integral
  4247. mov A, Temp1
  4248. cpl A
  4249. add A, #1
  4250. add A, Gov_Prop_Pwm
  4251. mov Temp1, A
  4252. ; Check result
  4253. jc governor_corr_int_max_pwm ; Is result above max?
  4254. jmp governor_store_int_corr ; No - store correction
  4255. governor_corr_int_max_pwm:
  4256. mov Temp1, #255 ; Load maximum pwm
  4257. governor_store_int_corr:
  4258. ; Store current pwm
  4259. mov Current_Pwm, Temp1
  4260. calc_governor_int_corr_exit:
  4261. ret
  4262. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4263. ;
  4264. ; Set pwm limit low rpm
  4265. ;
  4266. ; No assumptions
  4267. ;
  4268. ; Sets power limit for low rpms and disables demag for low rpms
  4269. ;
  4270. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4271. set_pwm_limit_low_rpm:
  4272. ; Set pwm limit and demag disable for low rpms
  4273. mov Temp1, #0FFh ; Default full power
  4274. jb Flags1.STARTUP_PHASE, set_pwm_limit_low_rpm_exit ; Exit if startup phase set
  4275. mov Temp2, #Pgm_Enable_Power_Prot ; Check if low RPM power protection is enabled
  4276. mov A, @Temp2
  4277. jz set_pwm_limit_low_rpm_exit ; Exit if disabled
  4278. mov A, Comm_Period4x_H
  4279. jz set_pwm_limit_low_rpm_exit ; Avoid divide by zero
  4280. mov A, #255 ; Divide 255 by Comm_Period4x_H
  4281. mov B, Comm_Period4x_H
  4282. div AB
  4283. mov B, Low_Rpm_Pwr_Slope ; Multiply by slope
  4284. jnb Flags1.INITIAL_RUN_PHASE, ($+6) ; More protection for initial run phase
  4285. mov B, #5
  4286. mul AB
  4287. mov Temp1, A ; Set new limit
  4288. xch A, B
  4289. jz ($+4) ; Limit to max
  4290. mov Temp1, #0FFh
  4291. clr C
  4292. mov A, Temp1 ; Limit to min
  4293. subb A, Pwm_Spoolup_Beg
  4294. jnc set_pwm_limit_low_rpm_exit
  4295. mov Temp1, Pwm_Spoolup_Beg
  4296. set_pwm_limit_low_rpm_exit:
  4297. mov Pwm_Limit_By_Rpm, Temp1
  4298. ret
  4299. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4300. ;
  4301. ; Set pwm limit high rpm
  4302. ;
  4303. ; No assumptions
  4304. ;
  4305. ; Sets power limit for high rpms
  4306. ;
  4307. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4308. set_pwm_limit_high_rpm:
  4309. IF MCU_48MHZ == 1
  4310. clr C
  4311. mov A, Comm_Period4x_L
  4312. subb A, #0C8h ; Limit Comm_Period to 200, which is 400k erpm
  4313. mov A, Comm_Period4x_H
  4314. subb A, #00h
  4315. ELSE
  4316. clr C
  4317. mov A, Comm_Period4x_L
  4318. subb A, #40h ; Limit Comm_Period to 320, which is 250k erpm
  4319. mov A, Comm_Period4x_H
  4320. subb A, #01h
  4321. ENDIF
  4322. mov A, Pwm_Limit_By_Rpm
  4323. jnc set_pwm_limit_high_rpm_inc_limit
  4324. dec A
  4325. ajmp set_pwm_limit_high_rpm_store
  4326. set_pwm_limit_high_rpm_inc_limit:
  4327. inc A
  4328. set_pwm_limit_high_rpm_store:
  4329. jz ($+4)
  4330. mov Pwm_Limit_By_Rpm, A
  4331. ret
  4332. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4333. ;
  4334. ; Measure lipo cells
  4335. ;
  4336. ; No assumptions
  4337. ;
  4338. ; Measure voltage and calculate lipo cells
  4339. ;
  4340. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4341. measure_lipo_cells:
  4342. IF MODE >= 1 ; Tail or multi
  4343. ; If not supported, then exit
  4344. jmp measure_lipo_exit
  4345. ENDIF
  4346. IF MODE == 0 ; Main
  4347. ; Load programmed low voltage limit
  4348. mov Temp1, #Pgm_Low_Voltage_Lim ; Load limit
  4349. mov A, @Temp1
  4350. mov Bit_Access, A ; Store in Bit_Access
  4351. ; Set commutation to BpFET on
  4352. call comm5comm6
  4353. ; Start adc
  4354. Start_Adc
  4355. ; Wait for ADC reference to settle, and then start again
  4356. call wait1ms
  4357. Start_Adc
  4358. ; Wait for ADC conversion to complete
  4359. measure_lipo_wait_adc:
  4360. jnb AD0INT, measure_lipo_wait_adc
  4361. ; Read ADC result
  4362. Read_Adc_Result
  4363. ; Stop ADC
  4364. Stop_Adc
  4365. ; Switch power off
  4366. call switch_power_off
  4367. ; Set limit step
  4368. mov Lipo_Adc_Limit_L, #ADC_LIMIT_L
  4369. mov Lipo_Adc_Limit_H, #ADC_LIMIT_H
  4370. clr C
  4371. mov A, #ADC_LIMIT_H ; Divide 3.0V value by 2
  4372. rrc A
  4373. mov Temp6, A
  4374. mov A, #ADC_LIMIT_L
  4375. jz measure_lipo_exit ; Exit if disabled
  4376. rrc A
  4377. mov Temp5, A
  4378. mov A, #ADC_LIMIT_L ; Calculate 1.5*3.0V=4.5V value
  4379. add A, Temp5
  4380. mov Temp5, A
  4381. mov A, #ADC_LIMIT_H
  4382. addc A, Temp6
  4383. mov Temp6, A
  4384. mov A, Temp5 ; Copy step
  4385. mov Temp3, A
  4386. mov A, Temp6
  4387. mov Temp4, A
  4388. measure_lipo_cell_loop:
  4389. ; Check voltage against xS lower limit
  4390. clr C
  4391. mov A, Temp1
  4392. subb A, Temp3 ; Voltage above limit?
  4393. mov A, Temp2
  4394. subb A, Temp4
  4395. jc measure_lipo_adjust ; No - branch
  4396. ; Set xS voltage limit
  4397. mov A, Lipo_Adc_Limit_L
  4398. add A, #ADC_LIMIT_L
  4399. mov Lipo_Adc_Limit_L, A
  4400. mov A, Lipo_Adc_Limit_H
  4401. addc A, #ADC_LIMIT_H
  4402. mov Lipo_Adc_Limit_H, A
  4403. ; Set (x+1)S lower limit
  4404. mov A, Temp3
  4405. add A, Temp5 ; Add step
  4406. mov Temp3, A
  4407. mov A, Temp4
  4408. addc A, Temp6
  4409. mov Temp4, A
  4410. jmp measure_lipo_cell_loop ; Check for one more battery cell
  4411. measure_lipo_adjust:
  4412. mov Temp7, Lipo_Adc_Limit_L
  4413. mov Temp8, Lipo_Adc_Limit_H
  4414. ; Calculate 3.125%
  4415. clr C
  4416. mov A, Lipo_Adc_Limit_H
  4417. rrc A
  4418. mov Temp2, A
  4419. mov A, Lipo_Adc_Limit_L
  4420. rrc A
  4421. mov Temp1, A ; After this 50%
  4422. clr C
  4423. mov A, Temp2
  4424. rrc A
  4425. mov Temp2, A
  4426. mov A, Temp1
  4427. rrc A
  4428. mov Temp1, A ; After this 25%
  4429. ; Divide three times to get to 3.125%
  4430. mov Temp3, #3
  4431. measure_lipo_divide_loop:
  4432. clr C
  4433. mov A, Temp2
  4434. rrc A
  4435. mov Temp2, A
  4436. mov A, Temp1
  4437. rrc A
  4438. mov Temp1, A
  4439. djnz Temp3, measure_lipo_divide_loop
  4440. ; Add the programmed number of 0.1V (or 3.125% increments)
  4441. mov Temp3, Bit_Access ; Load programmed limit (Bit_Access has Pgm_Low_Voltage_Lim)
  4442. dec Temp3
  4443. jnz measure_lipo_limit_on ; Is low voltage limiting on?
  4444. mov Lipo_Adc_Limit_L, #0 ; No - set limit to zero
  4445. mov Lipo_Adc_Limit_H, #0
  4446. jmp measure_lipo_exit
  4447. measure_lipo_limit_on:
  4448. dec Temp3
  4449. mov A, Temp3
  4450. jz measure_lipo_update
  4451. measure_lipo_add_loop:
  4452. mov A, Temp7 ; Add 3.125%
  4453. add A, Temp1
  4454. mov Temp7, A
  4455. mov A, Temp8
  4456. addc A, Temp2
  4457. mov Temp8, A
  4458. djnz Temp3, measure_lipo_add_loop
  4459. measure_lipo_update:
  4460. ; Set ADC limit
  4461. mov Lipo_Adc_Limit_L, Temp7
  4462. mov Lipo_Adc_Limit_H, Temp8
  4463. ENDIF
  4464. measure_lipo_exit:
  4465. ret
  4466. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4467. ;
  4468. ; Start ADC conversion
  4469. ;
  4470. ; No assumptions
  4471. ;
  4472. ; Start conversion used for measuring power supply voltage
  4473. ;
  4474. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4475. start_adc_conversion:
  4476. ; Start adc
  4477. Start_Adc
  4478. ret
  4479. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4480. ;
  4481. ; Check temperature, power supply voltage and limit power
  4482. ;
  4483. ; No assumptions
  4484. ;
  4485. ; Used to limit main motor power in order to maintain the required voltage
  4486. ;
  4487. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4488. check_temp_voltage_and_limit_power:
  4489. ; Load programmed low voltage limit
  4490. mov Temp1, #Pgm_Low_Voltage_Lim
  4491. mov A, @Temp1
  4492. mov Temp8, A ; Store in Temp8
  4493. ; Wait for ADC conversion to complete
  4494. jnb AD0INT, check_temp_voltage_and_limit_power
  4495. ; Read ADC result
  4496. Read_Adc_Result
  4497. ; Stop ADC
  4498. Stop_Adc
  4499. inc Adc_Conversion_Cnt ; Increment conversion counter
  4500. clr C
  4501. mov A, Adc_Conversion_Cnt ; Is conversion count equal to temp rate?
  4502. subb A, #TEMP_CHECK_RATE
  4503. jc check_voltage_start ; No - check voltage
  4504. mov Adc_Conversion_Cnt, #0 ; Yes - temperature check. Reset counter
  4505. mov A, Temp2 ; Move ADC MSB to Temp3
  4506. mov Temp3, A
  4507. mov Temp2, #Pgm_Enable_Temp_Prot ; Is temp protection enabled?
  4508. mov A, @Temp2
  4509. jz temp_check_exit ; No - branch
  4510. mov A, Temp3 ; Is temperature reading below 256?
  4511. jnz temp_average_inc_dec ; No - proceed
  4512. mov A, Current_Average_Temp ; Yes - decrement average
  4513. jz temp_average_updated ; Already zero - no change
  4514. jmp temp_average_dec ; Decrement
  4515. temp_average_inc_dec:
  4516. clr C
  4517. mov A, Temp1 ; Check if current temperature is above or below average
  4518. subb A, Current_Average_Temp
  4519. jz temp_average_updated_load_acc ; Equal - no change
  4520. mov A, Current_Average_Temp ; Above - increment average
  4521. jnc temp_average_inc
  4522. jz temp_average_updated ; Below - decrement average if average is not already zero
  4523. temp_average_dec:
  4524. dec A ; Decrement average
  4525. jmp temp_average_updated
  4526. temp_average_inc:
  4527. inc A ; Increment average
  4528. jz temp_average_dec
  4529. jmp temp_average_updated
  4530. temp_average_updated_load_acc:
  4531. mov A, Current_Average_Temp
  4532. temp_average_updated:
  4533. mov Current_Average_Temp, A
  4534. clr C
  4535. subb A, #TEMP_LIMIT ; Is temperature below first limit?
  4536. jc temp_check_exit ; Yes - exit
  4537. mov Pwm_Limit, #192 ; No - limit pwm
  4538. clr C
  4539. subb A, #TEMP_LIMIT_STEP ; Is temperature below second limit
  4540. jc temp_check_exit ; Yes - exit
  4541. mov Pwm_Limit, #128 ; No - limit pwm
  4542. clr C
  4543. subb A, #TEMP_LIMIT_STEP ; Is temperature below third limit
  4544. jc temp_check_exit ; Yes - exit
  4545. mov Pwm_Limit, #64 ; No - limit pwm
  4546. clr C
  4547. subb A, #TEMP_LIMIT_STEP ; Is temperature below final limit
  4548. jc temp_check_exit ; Yes - exit
  4549. mov Pwm_Limit, #0 ; No - limit pwm
  4550. temp_check_exit:
  4551. Set_Adc_Ip_Volt ; Select adc input for next conversion
  4552. ret
  4553. check_voltage_start:
  4554. IF MODE == 0 ; Main
  4555. ; Check if low voltage limiting is enabled
  4556. mov A, Temp8
  4557. clr C
  4558. subb A, #1 ; Is low voltage limit disabled?
  4559. jz check_voltage_good ; Yes - voltage declared good
  4560. mov A, #ADC_LIMIT_L ; Is low voltage limit zero (ESC does not support it)?
  4561. jz check_voltage_good ; Yes - voltage declared good
  4562. ; Check if ADC is saturated
  4563. clr C
  4564. mov A, Temp1
  4565. subb A, #0FFh
  4566. mov A, Temp2
  4567. subb A, #03h
  4568. jnc check_voltage_good ; ADC saturated, can not make judgement
  4569. ; Check voltage against limit
  4570. clr C
  4571. mov A, Temp1
  4572. subb A, Lipo_Adc_Limit_L
  4573. mov A, Temp2
  4574. subb A, Lipo_Adc_Limit_H
  4575. jnc check_voltage_good ; If voltage above limit - branch
  4576. ; Decrease pwm limit
  4577. mov A, Pwm_Limit
  4578. jz check_voltage_lim ; If limit zero - branch
  4579. dec Pwm_Limit ; Decrement limit
  4580. jmp check_voltage_lim
  4581. check_voltage_good:
  4582. ; Increase pwm limit
  4583. mov A, Pwm_Limit
  4584. cpl A
  4585. jz check_voltage_lim ; If limit max - branch
  4586. inc Pwm_Limit ; Increment limit
  4587. check_voltage_lim:
  4588. mov Temp1, Pwm_Limit ; Set limit
  4589. clr C
  4590. mov A, Current_Pwm
  4591. subb A, Temp1
  4592. jnc check_voltage_spoolup_lim ; If current pwm above limit - branch and limit
  4593. mov Temp1, Current_Pwm ; Set current pwm (no limiting)
  4594. check_voltage_spoolup_lim:
  4595. ; Slow spoolup
  4596. clr C
  4597. mov A, Temp1
  4598. subb A, Pwm_Limit_Spoolup
  4599. jc check_voltage_exit ; If current pwm below limit - branch
  4600. mov Temp1, Pwm_Limit_Spoolup
  4601. mov A, Pwm_Limit_Spoolup ; Check if spoolup limit is max
  4602. cpl A
  4603. jz check_voltage_exit ; If max - branch
  4604. mov Pwm_Limit, Pwm_Limit_Spoolup ; Set pwm limit to spoolup limit during ramp (to avoid governor integral buildup)
  4605. check_voltage_exit:
  4606. mov Current_Pwm_Limited, Temp1
  4607. mov Current_Pwm_Lim_Dith, Temp1
  4608. ENDIF
  4609. IF MODE == 1 ; Tail
  4610. ; Increase pwm limit
  4611. mov A, Pwm_Limit
  4612. cpl A
  4613. jz check_voltage_lim ; If limit max - branch
  4614. inc Pwm_Limit ; Increment limit
  4615. check_voltage_lim:
  4616. ENDIF
  4617. IF MODE == 2 ; Multi
  4618. ; Increase pwm limit
  4619. mov A, Pwm_Limit
  4620. add A, #16
  4621. jnc ($+4) ; If not max - branch
  4622. mov A, #255
  4623. mov Pwm_Limit, A ; Increment limit
  4624. ; Set current pwm limited if closed loop mode
  4625. mov Temp2, #Pgm_Gov_Mode ; Governor mode?
  4626. cjne @Temp2, #4, ($+5)
  4627. ajmp check_voltage_pwm_done ; No - branch
  4628. clr C
  4629. mov Temp1, Pwm_Limit ; Set limit
  4630. mov A, Current_Pwm
  4631. subb A, Temp1
  4632. jnc check_voltage_low_rpm ; If current pwm above limit - branch and limit
  4633. mov Temp1, Current_Pwm ; Set current pwm (no limiting)
  4634. check_voltage_low_rpm:
  4635. ; Limit pwm for low rpms
  4636. clr C
  4637. mov A, Temp1 ; Check against limit
  4638. subb A, Pwm_Limit_By_Rpm
  4639. jc ($+4) ; If current pwm below limit - branch
  4640. mov Temp1, Pwm_Limit_By_Rpm ; Limit pwm
  4641. mov Current_Pwm_Limited, Temp1
  4642. mov Current_Pwm_Lim_Dith, Temp1
  4643. check_voltage_pwm_done:
  4644. ENDIF
  4645. ; Set adc mux for next conversion
  4646. mov A, Adc_Conversion_Cnt ; Is next conversion for temperature?
  4647. cjne A, #(TEMP_CHECK_RATE-1), check_voltage_ret
  4648. Set_Adc_Ip_Temp ; Select temp sensor for next conversion
  4649. check_voltage_ret:
  4650. ret
  4651. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4652. ;
  4653. ; Set startup PWM routine
  4654. ;
  4655. ; Either the SETTLE_PHASE or the STEPPER_PHASE flag must be set
  4656. ;
  4657. ; Used for pwm control during startup
  4658. ;
  4659. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4660. set_startup_pwm:
  4661. ; Adjust startup power
  4662. mov A, #PWM_START ; Set power
  4663. mov Temp2, #Pgm_Startup_Pwr_Decoded
  4664. mov B, @Temp2
  4665. mul AB
  4666. xch A, B
  4667. mov C, B.7 ; Multiply result by 2 (unity gain is 128)
  4668. rlc A
  4669. mov Temp1, A ; Transfer to Temp1
  4670. clr C
  4671. mov A, Temp1 ; Check against limit
  4672. subb A, Pwm_Limit
  4673. jc startup_pwm_set_pwm ; If pwm below limit - branch
  4674. mov Temp1, Pwm_Limit ; Limit pwm
  4675. startup_pwm_set_pwm:
  4676. ; Set pwm variables
  4677. mov Requested_Pwm, Temp1 ; Update requested pwm
  4678. mov Current_Pwm, Temp1 ; Update current pwm
  4679. mov Current_Pwm_Limited, Temp1 ; Update limited version of current pwm
  4680. mov Current_Pwm_Lim_Dith, Temp1
  4681. mov Pwm_Spoolup_Beg, Temp1 ; Yes - update spoolup beginning pwm (will use PWM_SETTLE or PWM_SETTLE/2)
  4682. ret
  4683. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4684. ;
  4685. ; Initialize timing routine
  4686. ;
  4687. ; No assumptions
  4688. ;
  4689. ; Part of initialization before motor start
  4690. ;
  4691. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4692. initialize_timing:
  4693. mov Comm_Period4x_L, #00h ; Set commutation period registers
  4694. mov Comm_Period4x_H, #0F0h
  4695. ret
  4696. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4697. ;
  4698. ; Calculate next commutation timing routine
  4699. ;
  4700. ; No assumptions
  4701. ;
  4702. ; Called immediately after each commutation
  4703. ; Also sets up timer 3 to wait advance timing
  4704. ; Two entry points are used
  4705. ;
  4706. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4707. calc_next_comm_timing: ; Entry point for run phase
  4708. ; Read commutation time
  4709. clr EA
  4710. mov TMR2CN, #20h ; Timer2 disabled
  4711. mov Temp1, TMR2L ; Load timer value
  4712. mov Temp2, TMR2H
  4713. mov Temp3, Timer2_X
  4714. jnb TF2H, ($+4) ; Check if interrupt is pending
  4715. inc Temp3 ; If it is pending, then timer has already wrapped
  4716. mov TMR2CN, #24h ; Timer2 enabled
  4717. setb EA
  4718. IF MCU_48MHZ == 1
  4719. clr C
  4720. mov A, Temp3
  4721. rrc A
  4722. mov Temp3, A
  4723. mov A, Temp2
  4724. rrc A
  4725. mov Temp2, A
  4726. mov A, Temp1
  4727. rrc A
  4728. mov Temp1, A
  4729. ENDIF
  4730. ; Calculate this commutation time
  4731. mov Temp4, Prev_Comm_L
  4732. mov Temp5, Prev_Comm_H
  4733. mov Prev_Comm_L, Temp1 ; Store timestamp as previous commutation
  4734. mov Prev_Comm_H, Temp2
  4735. clr C
  4736. mov A, Temp1
  4737. subb A, Temp4 ; Calculate the new commutation time
  4738. mov Temp1, A
  4739. mov A, Temp2
  4740. subb A, Temp5
  4741. jb Flags1.STARTUP_PHASE, calc_next_comm_startup
  4742. IF MCU_48MHZ == 1
  4743. anl A, #7Fh
  4744. ENDIF
  4745. mov Temp2, A
  4746. jnb Flags0.HIGH_RPM, ($+5) ; Branch if high rpm
  4747. ajmp calc_next_comm_timing_fast
  4748. ajmp calc_next_comm_normal
  4749. calc_next_comm_startup:
  4750. mov Temp6, Prev_Comm_X
  4751. mov Prev_Comm_X, Temp3 ; Store extended timestamp as previous commutation
  4752. mov Temp2, A
  4753. mov A, Temp3
  4754. subb A, Temp6 ; Calculate the new extended commutation time
  4755. IF MCU_48MHZ == 1
  4756. anl A, #7Fh
  4757. ENDIF
  4758. mov Temp3, A
  4759. jz calc_next_comm_startup_no_X
  4760. mov Temp1, #0FFh
  4761. mov Temp2, #0FFh
  4762. ajmp calc_next_comm_startup_average
  4763. calc_next_comm_startup_no_X:
  4764. mov Temp7, Prev_Prev_Comm_L
  4765. mov Temp8, Prev_Prev_Comm_H
  4766. mov Prev_Prev_Comm_L, Temp4
  4767. mov Prev_Prev_Comm_H, Temp5
  4768. mov Temp1, Prev_Comm_L ; Reload this commutation time
  4769. mov Temp2, Prev_Comm_H
  4770. clr C
  4771. mov A, Temp1
  4772. subb A, Temp7 ; Calculate the new commutation time based upon the two last commutations (to reduce sensitivity to offset)
  4773. mov Temp1, A
  4774. mov A, Temp2
  4775. subb A, Temp8
  4776. mov Temp2, A
  4777. calc_next_comm_startup_average:
  4778. clr C
  4779. mov A, Comm_Period4x_H ; Average with previous and save
  4780. rrc A
  4781. mov Temp4, A
  4782. mov A, Comm_Period4x_L
  4783. rrc A
  4784. mov Temp3, A
  4785. mov A, Temp1
  4786. add A, Temp3
  4787. mov Comm_Period4x_L, A
  4788. mov A, Temp2
  4789. addc A, Temp4
  4790. mov Comm_Period4x_H, A
  4791. jnc ($+8)
  4792. mov Comm_Period4x_L, #0FFh
  4793. mov Comm_Period4x_H, #0FFh
  4794. ajmp calc_new_wait_times_setup
  4795. calc_next_comm_normal:
  4796. ; Calculate new commutation time
  4797. mov Temp3, Comm_Period4x_L ; Comm_Period4x(-l-h) holds the time of 4 commutations
  4798. mov Temp4, Comm_Period4x_H
  4799. mov Temp5, Comm_Period4x_L ; Copy variables
  4800. mov Temp6, Comm_Period4x_H
  4801. mov Temp7, #4 ; Divide Comm_Period4x 4 times as default
  4802. mov Temp8, #2 ; Divide new commutation time 2 times as default
  4803. clr C
  4804. mov A, Temp4
  4805. subb A, #04h
  4806. jc calc_next_comm_avg_period_div
  4807. dec Temp7 ; Reduce averaging time constant for low speeds
  4808. dec Temp8
  4809. clr C
  4810. mov A, Temp4
  4811. subb A, #08h
  4812. jc calc_next_comm_avg_period_div
  4813. jb Flags1.INITIAL_RUN_PHASE, calc_next_comm_avg_period_div ; Do not average very fast during initial run
  4814. dec Temp7 ; Reduce averaging time constant more for even lower speeds
  4815. dec Temp8
  4816. calc_next_comm_avg_period_div:
  4817. clr C
  4818. mov A, Temp6
  4819. rrc A ; Divide by 2
  4820. mov Temp6, A
  4821. mov A, Temp5
  4822. rrc A
  4823. mov Temp5, A
  4824. djnz Temp7, calc_next_comm_avg_period_div
  4825. clr C
  4826. mov A, Temp3
  4827. subb A, Temp5 ; Subtract a fraction
  4828. mov Temp3, A
  4829. mov A, Temp4
  4830. subb A, Temp6
  4831. mov Temp4, A
  4832. mov A, Temp8 ; Divide new time
  4833. jz calc_next_comm_new_period_div_done
  4834. calc_next_comm_new_period_div:
  4835. clr C
  4836. mov A, Temp2
  4837. rrc A ; Divide by 2
  4838. mov Temp2, A
  4839. mov A, Temp1
  4840. rrc A
  4841. mov Temp1, A
  4842. djnz Temp8, calc_next_comm_new_period_div
  4843. calc_next_comm_new_period_div_done:
  4844. mov A, Temp3
  4845. add A, Temp1 ; Add the divided new time
  4846. mov Temp3, A
  4847. mov A, Temp4
  4848. addc A, Temp2
  4849. mov Temp4, A
  4850. mov Comm_Period4x_L, Temp3 ; Store Comm_Period4x_X
  4851. mov Comm_Period4x_H, Temp4
  4852. jnc calc_new_wait_times_setup; If period larger than 0xffff - go to slow case
  4853. mov Temp4, #0FFh
  4854. mov Comm_Period4x_L, Temp4 ; Set commutation period registers to very slow timing (0xffff)
  4855. mov Comm_Period4x_H, Temp4
  4856. calc_new_wait_times_setup:
  4857. ; Set high rpm bit (if above 156k erpm)
  4858. clr C
  4859. mov A, Temp4
  4860. subb A, #2
  4861. jnc ($+4)
  4862. setb Flags0.HIGH_RPM ; Set high rpm bit
  4863. ; Load programmed commutation timing
  4864. jnb Flags1.STARTUP_PHASE, calc_new_wait_per_startup_done ; Set dedicated timing during startup
  4865. mov Temp8, #3
  4866. ajmp calc_new_wait_per_demag_done
  4867. calc_new_wait_per_startup_done:
  4868. mov Temp1, #Pgm_Comm_Timing ; Load timing setting
  4869. mov A, @Temp1
  4870. mov Temp8, A ; Store in Temp8
  4871. clr C
  4872. mov A, Demag_Detected_Metric ; Check demag metric
  4873. subb A, #130
  4874. jc calc_new_wait_per_demag_done
  4875. inc Temp8 ; Increase timing
  4876. clr C
  4877. mov A, Demag_Detected_Metric
  4878. subb A, #160
  4879. jc ($+3)
  4880. inc Temp8 ; Increase timing again
  4881. clr C
  4882. mov A, Temp8 ; Limit timing to max
  4883. subb A, #6
  4884. jc ($+4)
  4885. mov Temp8, #5 ; Set timing to max
  4886. calc_new_wait_per_demag_done:
  4887. mov Temp7, #2 ; Set timing reduction
  4888. ; Load current commutation timing
  4889. mov A, Comm_Period4x_H ; Divide 4 times
  4890. swap A
  4891. anl A, #00Fh
  4892. mov Temp2, A
  4893. mov A, Comm_Period4x_H
  4894. swap A
  4895. anl A, #0F0h
  4896. mov Temp1, A
  4897. mov A, Comm_Period4x_L
  4898. swap A
  4899. anl A, #00Fh
  4900. add A, Temp1
  4901. mov Temp1, A
  4902. clr C
  4903. mov A, Temp1
  4904. subb A, Temp7
  4905. mov Temp3, A
  4906. mov A, Temp2
  4907. subb A, #0
  4908. mov Temp4, A
  4909. jc load_min_time ; Check that result is still positive
  4910. clr C
  4911. mov A, Temp3
  4912. subb A, #(COMM_TIME_MIN SHL 1)
  4913. mov A, Temp4
  4914. subb A, #0
  4915. jnc calc_new_wait_times_exit ; Check that result is still above minumum
  4916. load_min_time:
  4917. mov Temp3, #(COMM_TIME_MIN SHL 1)
  4918. clr A
  4919. mov Temp4, A
  4920. calc_new_wait_times_exit:
  4921. ajmp wait_advance_timing
  4922. ; Fast calculation (Comm_Period4x_H less than 2)
  4923. calc_next_comm_timing_fast:
  4924. ; Calculate new commutation time
  4925. mov Temp3, Comm_Period4x_L ; Comm_Period4x(-l-h) holds the time of 4 commutations
  4926. mov Temp4, Comm_Period4x_H
  4927. mov A, Temp4 ; Divide by 2 4 times
  4928. swap A
  4929. mov Temp7, A
  4930. mov A, Temp3
  4931. swap A
  4932. anl A, #0Fh
  4933. orl A, Temp7
  4934. mov Temp5, A
  4935. clr C
  4936. mov A, Temp3 ; Subtract a fraction
  4937. subb A, Temp5
  4938. mov Temp3, A
  4939. mov A, Temp4
  4940. subb A, #0
  4941. mov Temp4, A
  4942. clr C
  4943. mov A, Temp1
  4944. rrc A ; Divide by 2 2 times
  4945. clr C
  4946. rrc A
  4947. mov Temp1, A
  4948. mov A, Temp3 ; Add the divided new time
  4949. add A, Temp1
  4950. mov Temp3, A
  4951. mov A, Temp4
  4952. addc A, #0
  4953. mov Temp4, A
  4954. mov Comm_Period4x_L, Temp3 ; Store Comm_Period4x_X
  4955. mov Comm_Period4x_H, Temp4
  4956. clr C
  4957. mov A, Temp4 ; If erpm below 156k - go to normal case
  4958. subb A, #2
  4959. jc ($+4)
  4960. clr Flags0.HIGH_RPM ; Clear high rpm bit
  4961. mov Temp1, #2 ; Set timing reduction
  4962. mov A, Temp4 ; Divide by 2 4 times
  4963. swap A
  4964. mov Temp7, A
  4965. mov Temp4, #0
  4966. mov A, Temp3
  4967. swap A
  4968. anl A, #0Fh
  4969. orl A, Temp7
  4970. mov Temp3, A
  4971. clr C
  4972. mov A, Temp3
  4973. subb A, Temp1
  4974. mov Temp3, A
  4975. jc load_min_time_fast ; Check that result is still positive
  4976. clr C
  4977. subb A, #(COMM_TIME_MIN SHL 1)
  4978. jnc calc_new_wait_times_fast_done ; Check that result is still above minumum
  4979. load_min_time_fast:
  4980. mov Temp3, #(COMM_TIME_MIN SHL 1)
  4981. calc_new_wait_times_fast_done:
  4982. mov Temp1, #Pgm_Comm_Timing ; Load timing setting
  4983. mov A, @Temp1
  4984. mov Temp8, A ; Store in Temp8
  4985. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4986. ;
  4987. ; Wait advance timing routine
  4988. ;
  4989. ; No assumptions
  4990. ; NOTE: Be VERY careful if using temp registers. They are passed over this routine
  4991. ;
  4992. ; Waits for the advance timing to elapse and sets up the next zero cross wait
  4993. ;
  4994. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  4995. wait_advance_timing:
  4996. jnb Flags0.T3_PENDING, ($+5)
  4997. ajmp wait_advance_timing
  4998. ; Setup next wait time
  4999. mov TMR3RLL, Wt_ZC_Tout_Start_L
  5000. mov TMR3RLH, Wt_ZC_Tout_Start_H
  5001. setb Flags0.T3_PENDING
  5002. orl EIE1, #80h ; Enable timer3 interrupts
  5003. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5004. ;
  5005. ; Calculate new wait times routine
  5006. ;
  5007. ; No assumptions
  5008. ;
  5009. ; Calculates new wait times
  5010. ;
  5011. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5012. calc_new_wait_times:
  5013. clr C
  5014. clr A
  5015. subb A, Temp3 ; Negate
  5016. mov Temp1, A
  5017. clr A
  5018. subb A, Temp4
  5019. mov Temp2, A
  5020. IF MCU_48MHZ == 1
  5021. clr C
  5022. mov A, Temp1 ; Multiply by 2
  5023. rlc A
  5024. mov Temp1, A
  5025. mov A, Temp2
  5026. rlc A
  5027. mov Temp2, A
  5028. ENDIF
  5029. jnb Flags0.HIGH_RPM, ($+5) ; Branch if high rpm
  5030. ajmp calc_new_wait_times_fast
  5031. mov A, Temp1 ; Copy values
  5032. mov Temp3, A
  5033. mov A, Temp2
  5034. mov Temp4, A
  5035. setb C ; Negative numbers - set carry
  5036. mov A, Temp2
  5037. rrc A ; Divide by 2
  5038. mov Temp6, A
  5039. mov A, Temp1
  5040. rrc A
  5041. mov Temp5, A
  5042. mov Wt_Zc_Tout_Start_L, Temp1; Set 15deg time for zero cross scan timeout
  5043. mov Wt_Zc_Tout_Start_H, Temp2
  5044. clr C
  5045. mov A, Temp8 ; (Temp8 has Pgm_Comm_Timing)
  5046. subb A, #3 ; Is timing normal?
  5047. jz store_times_decrease ; Yes - branch
  5048. mov A, Temp8
  5049. jb ACC.0, adjust_timing_two_steps ; If an odd number - branch
  5050. mov A, Temp1 ; Add 7.5deg and store in Temp1/2
  5051. add A, Temp5
  5052. mov Temp1, A
  5053. mov A, Temp2
  5054. addc A, Temp6
  5055. mov Temp2, A
  5056. mov A, Temp5 ; Store 7.5deg in Temp3/4
  5057. mov Temp3, A
  5058. mov A, Temp6
  5059. mov Temp4, A
  5060. jmp store_times_up_or_down
  5061. adjust_timing_two_steps:
  5062. mov A, Temp1 ; Add 15deg and store in Temp1/2
  5063. add A, Temp1
  5064. mov Temp1, A
  5065. mov A, Temp2
  5066. addc A, Temp2
  5067. mov Temp2, A
  5068. clr C
  5069. mov A, Temp1
  5070. add A, #(COMM_TIME_MIN SHL 1)
  5071. mov Temp1, A
  5072. mov A, Temp2
  5073. addc A, #0
  5074. mov Temp2, A
  5075. mov Temp3, #-(COMM_TIME_MIN SHL 1); Store minimum time in Temp3/4
  5076. mov Temp4, #0FFh
  5077. store_times_up_or_down:
  5078. clr C
  5079. mov A, Temp8
  5080. subb A, #3 ; Is timing higher than normal?
  5081. jc store_times_decrease ; No - branch
  5082. store_times_increase:
  5083. mov Wt_Comm_Start_L, Temp3 ; Now commutation time (~60deg) divided by 4 (~15deg nominal)
  5084. mov Wt_Comm_Start_H, Temp4
  5085. mov Wt_Adv_Start_L, Temp1 ; New commutation advance time (~15deg nominal)
  5086. mov Wt_Adv_Start_H, Temp2
  5087. mov Wt_Zc_Scan_Start_L, Temp5 ; Use this value for zero cross scan delay (7.5deg)
  5088. mov Wt_Zc_Scan_Start_H, Temp6
  5089. ajmp wait_before_zc_scan
  5090. store_times_decrease:
  5091. mov Wt_Comm_Start_L, Temp1 ; Now commutation time (~60deg) divided by 4 (~15deg nominal)
  5092. mov Wt_Comm_Start_H, Temp2
  5093. mov Wt_Adv_Start_L, Temp3 ; New commutation advance time (~15deg nominal)
  5094. mov Wt_Adv_Start_H, Temp4
  5095. mov Wt_Zc_Scan_Start_L, Temp5 ; Use this value for zero cross scan delay (7.5deg)
  5096. mov Wt_Zc_Scan_Start_H, Temp6
  5097. jnb Flags1.STARTUP_PHASE, store_times_exit
  5098. mov Wt_Comm_Start_L, #0F0h ; Set very short delays for all but advance time during startup, in order to widen zero cross capture range
  5099. mov Wt_Comm_Start_H, #0FFh
  5100. mov Wt_Zc_Scan_Start_L, #0F0h
  5101. mov Wt_Zc_Scan_Start_H, #0FFh
  5102. mov Wt_Zc_Tout_Start_L, #0F0h
  5103. mov Wt_Zc_Tout_Start_H, #0FFh
  5104. store_times_exit:
  5105. ajmp wait_before_zc_scan
  5106. calc_new_wait_times_fast:
  5107. mov A, Temp1 ; Copy values
  5108. mov Temp3, A
  5109. setb C ; Negative numbers - set carry
  5110. mov A, Temp1 ; Divide by 2
  5111. rrc A
  5112. mov Temp5, A
  5113. mov Wt_Zc_Tout_Start_L, Temp1; Set 15deg time for zero cross scan timeout
  5114. clr C
  5115. mov A, Temp8 ; (Temp8 has Pgm_Comm_Timing)
  5116. subb A, #3 ; Is timing normal?
  5117. jz store_times_decrease_fast; Yes - branch
  5118. mov A, Temp8
  5119. jb ACC.0, adjust_timing_two_steps_fast ; If an odd number - branch
  5120. mov A, Temp1 ; Add 7.5deg and store in Temp1
  5121. add A, Temp5
  5122. mov Temp1, A
  5123. mov A, Temp5 ; Store 7.5deg in Temp3
  5124. mov Temp3, A
  5125. ajmp store_times_up_or_down_fast
  5126. adjust_timing_two_steps_fast:
  5127. mov A, Temp1 ; Add 15deg and store in Temp1
  5128. add A, Temp1
  5129. add A, #(COMM_TIME_MIN SHL 1)
  5130. mov Temp1, A
  5131. mov Temp3, #-(COMM_TIME_MIN SHL 1) ; Store minimum time in Temp3
  5132. store_times_up_or_down_fast:
  5133. clr C
  5134. mov A, Temp8
  5135. subb A, #3 ; Is timing higher than normal?
  5136. jc store_times_decrease_fast; No - branch
  5137. store_times_increase_fast:
  5138. mov Wt_Comm_Start_L, Temp3 ; Now commutation time (~60deg) divided by 4 (~15deg nominal)
  5139. mov Wt_Adv_Start_L, Temp1 ; New commutation advance time (~15deg nominal)
  5140. mov Wt_Zc_Scan_Start_L, Temp5 ; Use this value for zero cross scan delay (7.5deg)
  5141. ajmp wait_before_zc_scan
  5142. store_times_decrease_fast:
  5143. mov Wt_Comm_Start_L, Temp1 ; Now commutation time (~60deg) divided by 4 (~15deg nominal)
  5144. mov Wt_Adv_Start_L, Temp3 ; New commutation advance time (~15deg nominal)
  5145. mov Wt_Zc_Scan_Start_L, Temp5 ; Use this value for zero cross scan delay (7.5deg)
  5146. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5147. ;
  5148. ; Wait before zero cross scan routine
  5149. ;
  5150. ; No assumptions
  5151. ;
  5152. ; Waits for the zero cross scan wait time to elapse
  5153. ; Also sets up timer 3 for the zero cross scan timeout time
  5154. ;
  5155. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5156. wait_before_zc_scan:
  5157. ; Calculate random number
  5158. mov A, Random
  5159. clr C
  5160. rlc A
  5161. jnc wait_before_zc_scan_rand
  5162. xrl A, #06Bh ; Sequence length of 35, when initialized to 1
  5163. wait_before_zc_scan_rand:
  5164. mov Random, A
  5165. wait_before_zc_scan_wait:
  5166. jnb Flags0.T3_PENDING, ($+5)
  5167. ajmp wait_before_zc_scan_wait
  5168. mov Startup_Zc_Timeout_Cntd, #2
  5169. setup_zc_scan_timeout:
  5170. setb Flags0.T3_PENDING
  5171. orl EIE1, #80h ; Enable timer3 interrupts
  5172. mov A, Flags1
  5173. anl A, #((1 SHL STARTUP_PHASE)+(1 SHL INITIAL_RUN_PHASE))
  5174. jz wait_before_zc_scan_exit
  5175. mov Temp1, Comm_Period4x_L ; Set long timeout when starting
  5176. mov Temp2, Comm_Period4x_H
  5177. clr C
  5178. mov A, Temp2
  5179. rrc A
  5180. mov Temp2, A
  5181. mov A, Temp1
  5182. rrc A
  5183. mov Temp1, A
  5184. IF MCU_48MHZ == 0
  5185. clr C
  5186. mov A, Temp2
  5187. rrc A
  5188. mov Temp2, A
  5189. mov A, Temp1
  5190. rrc A
  5191. mov Temp1, A
  5192. ENDIF
  5193. jnb Flags1.STARTUP_PHASE, setup_zc_scan_timeout_startup_done
  5194. mov A, Temp2
  5195. add A, #40h ; Increase timeout somewhat to avoid false wind up
  5196. mov Temp2, A
  5197. setup_zc_scan_timeout_startup_done:
  5198. clr EA
  5199. anl EIE1, #7Fh ; Disable timer3 interrupts
  5200. mov TMR3CN, #00h ; Timer3 disabled and interrupt flag cleared
  5201. clr C
  5202. clr A
  5203. subb A, Temp1 ; Set timeout
  5204. mov TMR3L, A
  5205. clr A
  5206. subb A, Temp2
  5207. mov TMR3H, A
  5208. mov TMR3CN, #04h ; Timer3 enabled and interrupt flag cleared
  5209. setb Flags0.T3_PENDING
  5210. orl EIE1, #80h ; Enable timer3 interrupts
  5211. setb EA
  5212. wait_before_zc_scan_exit:
  5213. ret
  5214. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5215. ;
  5216. ; Wait for comparator to go low/high routines
  5217. ;
  5218. ; No assumptions
  5219. ;
  5220. ; Waits for the zero cross scan wait time to elapse
  5221. ; Then scans for comparator going low/high
  5222. ;
  5223. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5224. wait_for_comp_out_low:
  5225. setb Flags0.DEMAG_DETECTED ; Set demag detected flag as default
  5226. mov Comparator_Read_Cnt, #0 ; Reset number of comparator reads
  5227. mov Bit_Access, #00h ; Desired comparator output
  5228. jnb Flags1.DIR_CHANGE_BRAKE, ($+6)
  5229. mov Bit_Access, #40h
  5230. jmp wait_for_comp_out_start
  5231. wait_for_comp_out_high:
  5232. setb Flags0.DEMAG_DETECTED ; Set demag detected flag as default
  5233. mov Comparator_Read_Cnt, #0 ; Reset number of comparator reads
  5234. mov Bit_Access, #40h ; Desired comparator output
  5235. jnb Flags1.DIR_CHANGE_BRAKE, ($+6)
  5236. mov Bit_Access, #00h
  5237. wait_for_comp_out_start:
  5238. ; Set number of comparator readings
  5239. mov Temp1, #1 ; Number of OK readings required
  5240. mov Temp2, #1 ; Max number of readings required
  5241. jb Flags0.HIGH_RPM, comp_scale_samples ; Branch if high rpm
  5242. mov A, Flags1 ; Clear demag detected flag if start phases
  5243. anl A, #((1 SHL STARTUP_PHASE)+(1 SHL INITIAL_RUN_PHASE))
  5244. jz ($+4)
  5245. clr Flags0.DEMAG_DETECTED
  5246. mov Temp2, #20 ; Too low value (~<15) causes rough running at pwm harmonics. Too high a value (~>35) causes the RCT4215 630 to run rough on full throttle
  5247. mov A, Comm_Period4x_H ; Set number of readings higher for lower speeds
  5248. clr C
  5249. rrc A
  5250. jnz ($+3)
  5251. inc A
  5252. mov Temp1, A
  5253. clr C
  5254. subb A, #20
  5255. jc ($+4)
  5256. mov Temp1, #20
  5257. jnb Flags1.STARTUP_PHASE, comp_scale_samples
  5258. mov Temp1, #27 ; Set many samples during startup, approximately one pwm period
  5259. mov Temp2, #27
  5260. comp_scale_samples:
  5261. IF MCU_48MHZ == 1
  5262. clr C
  5263. mov A, Temp1
  5264. rlc A
  5265. mov Temp1, A
  5266. clr C
  5267. mov A, Temp2
  5268. rlc A
  5269. mov Temp2, A
  5270. ENDIF
  5271. comp_check_timeout:
  5272. jb Flags0.T3_PENDING, comp_check_timeout_not_timed_out ; Has zero cross scan timeout elapsed?
  5273. mov A, Comparator_Read_Cnt ; Check that comparator has been read
  5274. jz comp_check_timeout_not_timed_out ; If not read - branch
  5275. jnb Flags1.STARTUP_PHASE, comp_check_timeout_timeout_extended ; Extend timeout during startup
  5276. djnz Startup_Zc_Timeout_Cntd, comp_check_timeout_extend_timeout
  5277. comp_check_timeout_timeout_extended:
  5278. setb Flags1.COMP_TIMED_OUT
  5279. ajmp setup_comm_wait
  5280. comp_check_timeout_extend_timeout:
  5281. call setup_zc_scan_timeout
  5282. comp_check_timeout_not_timed_out:
  5283. inc Comparator_Read_Cnt ; Increment comparator read count
  5284. Read_Comp_Out ; Read comparator output
  5285. anl A, #40h
  5286. cjne A, Bit_Access, comp_read_wrong
  5287. ajmp comp_read_ok
  5288. comp_read_wrong:
  5289. jnb Flags1.STARTUP_PHASE, comp_read_wrong_not_startup
  5290. inc Temp1 ; Increment number of OK readings required
  5291. clr C
  5292. mov A, Temp1
  5293. subb A, Temp2 ; If above initial requirement - go back and restart
  5294. jc ($+3)
  5295. dec Temp1
  5296. ajmp comp_check_timeout ; Continue to look for good ones
  5297. comp_read_wrong_not_startup:
  5298. jb Flags0.DEMAG_DETECTED, comp_read_wrong_extend_timeout
  5299. inc Temp1 ; Increment number of OK readings required
  5300. clr C
  5301. mov A, Temp1
  5302. subb A, Temp2
  5303. jc ($+4)
  5304. ajmp wait_for_comp_out_start ; If above initial requirement - go back and restart
  5305. ajmp comp_check_timeout ; Otherwise - take another reading
  5306. comp_read_wrong_extend_timeout:
  5307. clr Flags0.DEMAG_DETECTED ; Clear demag detected flag
  5308. clr EA
  5309. anl EIE1, #7Fh ; Disable timer3 interrupts
  5310. mov TMR3CN, #00h ; Timer3 disabled and interrupt flag cleared
  5311. jnb Flags0.HIGH_RPM, comp_read_wrong_low_rpm ; Branch if not high rpm
  5312. mov TMR3L, #00h ; Set timeout to ~1ms
  5313. IF MCU_48MHZ == 1
  5314. mov TMR3H, #0F0h
  5315. ELSE
  5316. mov TMR3H, #0F8h
  5317. ENDIF
  5318. comp_read_wrong_timeout_set:
  5319. mov TMR3CN, #04h ; Timer3 enabled and interrupt flag cleared
  5320. setb Flags0.T3_PENDING
  5321. orl EIE1, #80h ; Enable timer3 interrupts
  5322. setb EA
  5323. ajmp wait_for_comp_out_start ; If comparator output is not correct - go back and restart
  5324. comp_read_wrong_low_rpm:
  5325. mov A, Comm_Period4x_H ; Set timeout to ~4x comm period 4x value
  5326. mov Temp7, #0FFh ; Default to long
  5327. IF MCU_48MHZ == 1
  5328. clr C
  5329. rlc A
  5330. jc comp_read_wrong_load_timeout
  5331. ENDIF
  5332. clr C
  5333. rlc A
  5334. jc comp_read_wrong_load_timeout
  5335. clr C
  5336. rlc A
  5337. jc comp_read_wrong_load_timeout
  5338. mov Temp7, A
  5339. comp_read_wrong_load_timeout:
  5340. clr C
  5341. clr A
  5342. subb A, Temp7
  5343. mov TMR3L, #0
  5344. mov TMR3H, A
  5345. ajmp comp_read_wrong_timeout_set
  5346. comp_read_ok:
  5347. clr C
  5348. mov A, Startup_Cnt ; Force a timeout for the first commutation
  5349. subb A, #1
  5350. jnc ($+4)
  5351. ajmp wait_for_comp_out_start
  5352. jnb Flags0.DEMAG_DETECTED, ($+5) ; Do not accept correct comparator output if it is demag
  5353. ajmp wait_for_comp_out_start
  5354. djnz Temp1, comp_read_ok_jmp ; Decrement readings counter - repeat comparator reading if not zero
  5355. ajmp ($+4)
  5356. comp_read_ok_jmp:
  5357. ajmp comp_check_timeout
  5358. clr Flags1.COMP_TIMED_OUT
  5359. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5360. ;
  5361. ; Setup commutation timing routine
  5362. ;
  5363. ; No assumptions
  5364. ;
  5365. ; Sets up and starts wait from commutation to zero cross
  5366. ;
  5367. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5368. setup_comm_wait:
  5369. clr EA
  5370. anl EIE1, #7Fh ; Disable timer3 interrupts
  5371. mov TMR3CN, #00h ; Timer3 disabled and interrupt flag cleared
  5372. mov TMR3L, Wt_Comm_Start_L
  5373. mov TMR3H, Wt_Comm_Start_H
  5374. mov TMR3CN, #04h ; Timer3 enabled and interrupt flag cleared
  5375. ; Setup next wait time
  5376. mov TMR3RLL, Wt_Adv_Start_L
  5377. mov TMR3RLH, Wt_Adv_Start_H
  5378. setb Flags0.T3_PENDING
  5379. orl EIE1, #80h ; Enable timer3 interrupts
  5380. setb EA ; Enable interrupts again
  5381. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5382. ;
  5383. ; Evaluate comparator integrity
  5384. ;
  5385. ; No assumptions
  5386. ;
  5387. ; Checks comparator signal behaviour versus expected behaviour
  5388. ;
  5389. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5390. evaluate_comparator_integrity:
  5391. mov A, Flags1
  5392. anl A, #((1 SHL STARTUP_PHASE)+(1 SHL INITIAL_RUN_PHASE))
  5393. jz eval_comp_check_timeout
  5394. jb Flags1.INITIAL_RUN_PHASE, ($+5) ; Do not increment beyond startup phase
  5395. inc Startup_Cnt ; Increment counter
  5396. jmp eval_comp_exit
  5397. eval_comp_check_timeout:
  5398. jnb Flags1.COMP_TIMED_OUT, eval_comp_exit ; Has timeout elapsed?
  5399. jb Flags1.DIR_CHANGE_BRAKE, eval_comp_exit ; Do not exit run mode if it is braking
  5400. jb Flags0.DEMAG_DETECTED, eval_comp_exit ; Do not exit run mode if it is a demag situation
  5401. dec SP ; Routine exit without "ret" command
  5402. dec SP
  5403. ljmp run_to_wait_for_power_on_fail ; Yes - exit run mode
  5404. eval_comp_exit:
  5405. ret
  5406. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5407. ;
  5408. ; Wait for commutation routine
  5409. ;
  5410. ; No assumptions
  5411. ;
  5412. ; Waits from zero cross to commutation
  5413. ;
  5414. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5415. wait_for_comm:
  5416. ; Update demag metric
  5417. mov Temp1, #0
  5418. jnb Flags0.DEMAG_DETECTED, ($+5)
  5419. mov Temp1, #1
  5420. mov A, Demag_Detected_Metric ; Sliding average of 8, 256 when demag and 0 when not. Limited to minimum 120
  5421. mov B, #7
  5422. mul AB ; Multiply by 7
  5423. mov Temp2, A
  5424. mov A, B ; Add new value for current demag status
  5425. add A, Temp1
  5426. mov B, A
  5427. mov A, Temp2
  5428. mov C, B.0 ; Divide by 8
  5429. rrc A
  5430. mov C, B.1
  5431. rrc A
  5432. mov C, B.2
  5433. rrc A
  5434. mov Demag_Detected_Metric, A
  5435. clr C
  5436. subb A, #120 ; Limit to minimum 120
  5437. jnc ($+5)
  5438. mov Demag_Detected_Metric, #120
  5439. clr C
  5440. mov A, Demag_Detected_Metric ; Check demag metric
  5441. subb A, Demag_Pwr_Off_Thresh
  5442. jc wait_for_comm_wait ; Cut power if many consecutive demags. This will help retain sync during hard accelerations
  5443. setb Flags0.DEMAG_CUT_POWER ; Set demag power cut flag
  5444. IF NFETON_DELAY NE 0
  5445. All_nFETs_off
  5446. ELSE
  5447. En_Off ; For EN/PWM style drivers
  5448. ENDIF
  5449. wait_for_comm_wait:
  5450. jnb Flags0.T3_PENDING, ($+5)
  5451. ajmp wait_for_comm_wait
  5452. ; Setup next wait time
  5453. mov TMR3RLL, Wt_Zc_Scan_Start_L
  5454. mov TMR3RLH, Wt_Zc_Scan_Start_H
  5455. setb Flags0.T3_PENDING
  5456. orl EIE1, #80h ; Enable timer3 interrupts
  5457. ret
  5458. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5459. ;
  5460. ; Commutation routines
  5461. ;
  5462. ; No assumptions
  5463. ;
  5464. ; Performs commutation switching
  5465. ; Damped routines uses all pfets on when in pwm off to dampen the motor
  5466. ;
  5467. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5468. ; Comm phase 1 to comm phase 2
  5469. comm1comm2:
  5470. Set_RPM_Out
  5471. jb Flags3.PGM_DIR_REV, comm12_rev
  5472. clr EA ; Disable all interrupts
  5473. mov Comm_Phase, #2
  5474. BpFET_off ; Turn off pfet
  5475. ApFET_on ; Turn on pfet
  5476. jnb Flags0.PWM_ON, comm12_nfet_done ; Is pwm on?
  5477. CnFET_on ; Pwm on - turn on nfet
  5478. comm12_nfet_done:
  5479. setb EA
  5480. Set_Comp_Phase_B ; Set comparator phase
  5481. jmp comm_exit
  5482. comm12_rev:
  5483. clr EA ; Disable all interrupts
  5484. mov Comm_Phase, #2
  5485. BpFET_off ; Turn off pfet
  5486. CpFET_on ; Turn on pfet (reverse)
  5487. jnb Flags0.PWM_ON, comm12_nfet_done_rev ; Is pwm on?
  5488. AnFET_on ; Pwm on - turn on nfet
  5489. comm12_nfet_done_rev:
  5490. setb EA
  5491. Set_Comp_Phase_B ; Set comparator phase
  5492. jmp comm_exit
  5493. ; Comm phase 2 to comm phase 3
  5494. comm2comm3:
  5495. Clear_RPM_Out
  5496. jnb Flags2.PGM_PWMOFF_DAMPED, comm23_nondamp
  5497. ; Comm2Comm3 Damped
  5498. jb Flags3.PGM_DIR_REV, comm23_damp_rev
  5499. clr EA ; Disable all interrupts
  5500. mov Comm_Phase, #3
  5501. mov DPTR, #pwm_bfet_damped
  5502. mov DampingFET, #(1 SHL BpFET)
  5503. CnFET_off ; Turn off fets
  5504. CpFET_off
  5505. jnb Flags0.PWM_ON, comm23_nfet_off ; Is pwm on?
  5506. BnFET_on ; Pwm on - turn on nfet
  5507. ajmp comm23_fets_done
  5508. comm23_nfet_off:
  5509. BpFET_on ; Pwm off - switch damping fets
  5510. comm23_fets_done:
  5511. setb EA
  5512. Set_Comp_Phase_C ; Set comparator phase
  5513. ljmp comm_exit
  5514. ; Comm2Comm3 Damped reverse
  5515. comm23_damp_rev:
  5516. clr EA ; Disable all interrupts
  5517. mov Comm_Phase, #3
  5518. mov DPTR, #pwm_bfet_damped
  5519. mov DampingFET, #(1 SHL BpFET)
  5520. AnFET_off ; Turn off fets (reverse)
  5521. ApFET_off
  5522. jnb Flags0.PWM_ON, comm23_nfet_off_rev ; Is pwm on?
  5523. BnFET_on ; Pwm on - turn on nfet
  5524. ajmp comm23_fets_done_rev
  5525. comm23_nfet_off_rev:
  5526. BpFET_on ; Pwm off - switch damping fets
  5527. comm23_fets_done_rev:
  5528. setb EA
  5529. Set_Comp_Phase_A ; Set comparator phase (reverse)
  5530. ljmp comm_exit
  5531. ; Comm2Comm3 Non-damped
  5532. comm23_nondamp:
  5533. jb Flags3.PGM_DIR_REV, comm23_nondamp_rev
  5534. clr EA ; Disable all interrupts
  5535. mov Comm_Phase, #3
  5536. mov DPTR, #pwm_bfet
  5537. IF NFETON_DELAY == 0
  5538. mov DampingFET, #(1 SHL BpFET)
  5539. ENDIF
  5540. CnFET_off ; Turn off nfet
  5541. jnb Flags0.PWM_ON, comm23_nfet_done ; Is pwm on?
  5542. BnFET_on ; Yes - turn on nfet
  5543. comm23_nfet_done:
  5544. setb EA
  5545. Set_Comp_Phase_C ; Set comparator phase
  5546. ljmp comm_exit
  5547. ; Comm2Comm3 Non-damped reverse
  5548. comm23_nondamp_rev:
  5549. clr EA ; Disable all interrupts
  5550. mov Comm_Phase, #3
  5551. mov DPTR, #pwm_bfet
  5552. IF NFETON_DELAY == 0
  5553. mov DampingFET, #(1 SHL BpFET)
  5554. ENDIF
  5555. AnFET_off ; Turn off nfet (reverse)
  5556. jnb Flags0.PWM_ON, comm23_nfet_done_rev ; Is pwm on?
  5557. BnFET_on ; Yes - turn on nfet
  5558. comm23_nfet_done_rev:
  5559. setb EA
  5560. Set_Comp_Phase_A ; Set comparator phase (reverse)
  5561. ljmp comm_exit
  5562. ; Comm phase 3 to comm phase 4
  5563. comm3comm4:
  5564. Set_RPM_Out
  5565. jb Flags3.PGM_DIR_REV, comm34_rev
  5566. clr EA ; Disable all interrupts
  5567. mov Comm_Phase, #4
  5568. ApFET_off ; Turn off pfet
  5569. CpFET_on ; Turn on pfet
  5570. jnb Flags0.PWM_ON, comm34_nfet_done ; Is pwm on?
  5571. BnFET_on ; Pwm on - turn on nfet
  5572. comm34_nfet_done:
  5573. setb EA
  5574. Set_Comp_Phase_A ; Set comparator phase
  5575. jmp comm_exit
  5576. comm34_rev:
  5577. clr EA ; Disable all interrupts
  5578. mov Comm_Phase, #4
  5579. CpFET_off ; Turn off pfet (reverse)
  5580. ApFET_on ; Turn on pfet (reverse)
  5581. jnb Flags0.PWM_ON, comm34_nfet_done_rev ; Is pwm on?
  5582. BnFET_on ; Pwm on - turn on nfet
  5583. comm34_nfet_done_rev:
  5584. setb EA
  5585. Set_Comp_Phase_C ; Set comparator phase (reverse)
  5586. jmp comm_exit
  5587. ; Comm phase 4 to comm phase 5
  5588. comm4comm5:
  5589. Clear_RPM_Out
  5590. jnb Flags2.PGM_PWMOFF_DAMPED, comm45_nondamp
  5591. ; Comm4Comm5 Damped
  5592. jb Flags3.PGM_DIR_REV, comm45_damp_rev
  5593. clr EA ; Disable all interrupts
  5594. mov Comm_Phase, #5
  5595. mov DPTR, #pwm_afet_damped
  5596. mov DampingFET, #(1 SHL ApFET)
  5597. BnFET_off ; Turn off fets
  5598. BpFET_off
  5599. jnb Flags0.PWM_ON, comm45_nfet_off ; Is pwm on?
  5600. AnFET_on ; Pwm on - turn on nfet
  5601. ajmp comm45_fets_done
  5602. comm45_nfet_off:
  5603. ApFET_on ; Pwm off - switch damping fets
  5604. comm45_fets_done:
  5605. setb EA
  5606. Set_Comp_Phase_B ; Set comparator phase
  5607. ljmp comm_exit
  5608. ; Comm4Comm5 Damped reverse
  5609. comm45_damp_rev:
  5610. clr EA ; Disable all interrupts
  5611. mov Comm_Phase, #5
  5612. mov DPTR, #pwm_cfet_damped ; (reverse)
  5613. mov DampingFET, #(1 SHL CpFET) ; (reverse)
  5614. BnFET_off ; Turn off fets
  5615. BpFET_off
  5616. jnb Flags0.PWM_ON, comm45_nfet_off_rev ; Is pwm on?
  5617. CnFET_on ; Pwm on - turn on nfet (reverse)
  5618. ajmp comm45_fets_done_rev
  5619. comm45_nfet_off_rev:
  5620. CpFET_on ; Pwm off - switch damping fets (reverse)
  5621. comm45_fets_done_rev:
  5622. setb EA
  5623. Set_Comp_Phase_B ; Set comparator phase
  5624. ljmp comm_exit
  5625. ; Comm4Comm5 Non-damped
  5626. comm45_nondamp:
  5627. jb Flags3.PGM_DIR_REV, comm45_nondamp_rev
  5628. clr EA ; Disable all interrupts
  5629. mov Comm_Phase, #5
  5630. mov DPTR, #pwm_afet
  5631. IF NFETON_DELAY == 0
  5632. mov DampingFET, #(1 SHL ApFET)
  5633. ENDIF
  5634. BnFET_off ; Turn off nfet
  5635. jnb Flags0.PWM_ON, comm45_nfet_done ; Is pwm on?
  5636. AnFET_on ; Yes - turn on nfet
  5637. comm45_nfet_done:
  5638. setb EA
  5639. Set_Comp_Phase_B ; Set comparator phase
  5640. ljmp comm_exit
  5641. ; Comm4Comm5 Non-damped reverse
  5642. comm45_nondamp_rev:
  5643. clr EA ; Disable all interrupts
  5644. mov Comm_Phase, #5
  5645. mov DPTR, #pwm_cfet ; (reverse)
  5646. IF NFETON_DELAY == 0
  5647. mov DampingFET, #(1 SHL CpFET)
  5648. ENDIF
  5649. BnFET_off ; Turn off nfet
  5650. jnb Flags0.PWM_ON, comm45_nfet_done ; Is pwm on?
  5651. CnFET_on ; Yes - turn on nfet (reverse)
  5652. setb EA
  5653. Set_Comp_Phase_B ; Set comparator phase
  5654. ljmp comm_exit
  5655. ; Comm phase 5 to comm phase 6
  5656. comm5comm6:
  5657. Set_RPM_Out
  5658. jb Flags3.PGM_DIR_REV, comm56_rev
  5659. clr EA ; Disable all interrupts
  5660. mov Comm_Phase, #6
  5661. CpFET_off ; Turn off pfet
  5662. BpFET_on ; Turn on pfet
  5663. jnb Flags0.PWM_ON, comm56_nfet_done ; Is pwm on?
  5664. AnFET_on ; Pwm on - turn on nfet
  5665. comm56_nfet_done:
  5666. setb EA
  5667. Set_Comp_Phase_C ; Set comparator phase
  5668. jmp comm_exit
  5669. comm56_rev:
  5670. clr EA ; Disable all interrupts
  5671. mov Comm_Phase, #6
  5672. ApFET_off ; Turn off pfet (reverse)
  5673. BpFET_on ; Turn on pfet
  5674. jnb Flags0.PWM_ON, comm56_nfet_done_rev ; Is pwm on?
  5675. CnFET_on ; Pwm on - turn on nfet
  5676. comm56_nfet_done_rev:
  5677. setb EA
  5678. Set_Comp_Phase_A ; Set comparator phase (reverse)
  5679. jmp comm_exit
  5680. ; Comm phase 6 to comm phase 1
  5681. comm6comm1:
  5682. Clear_RPM_Out
  5683. jnb Flags2.PGM_PWMOFF_DAMPED, comm61_nondamp
  5684. ; Comm6Comm1 Damped
  5685. jb Flags3.PGM_DIR_REV, comm61_damp_rev
  5686. clr EA ; Disable all interrupts
  5687. mov Comm_Phase, #1
  5688. mov DPTR, #pwm_cfet_damped
  5689. mov DampingFET, #(1 SHL CpFET)
  5690. AnFET_off ; Turn off fets
  5691. ApFET_off
  5692. jnb Flags0.PWM_ON, comm61_nfet_off ; Is pwm on?
  5693. CnFET_on ; Pwm on - turn on nfet
  5694. ajmp comm61_fets_done
  5695. comm61_nfet_off:
  5696. CpFET_on ; Pwm off - switch damping fets
  5697. comm61_fets_done:
  5698. setb EA
  5699. Set_Comp_Phase_A ; Set comparator phase
  5700. ljmp comm_exit
  5701. ; Comm6Comm1 Damped reverse
  5702. comm61_damp_rev:
  5703. clr EA ; Disable all interrupts
  5704. mov Comm_Phase, #1
  5705. mov DPTR, #pwm_afet_damped ; (reverse)
  5706. mov DampingFET, #(1 SHL ApFET) ; (reverse)
  5707. CnFET_off ; Turn off fets (reverse)
  5708. CpFET_off
  5709. jnb Flags0.PWM_ON, comm61_nfet_off_rev ; Is pwm on?
  5710. AnFET_on ; Pwm on - turn on nfet
  5711. jmp comm61_fets_done_rev
  5712. comm61_nfet_off_rev:
  5713. ApFET_on ; Pwm off - switch damping fets (reverse)
  5714. comm61_fets_done_rev:
  5715. setb EA
  5716. Set_Comp_Phase_C ; Set comparator phase (reverse)
  5717. jmp comm_exit
  5718. ; Comm6Comm1 Non-damped
  5719. comm61_nondamp:
  5720. jb Flags3.PGM_DIR_REV, comm61_nondamp_rev
  5721. clr EA ; Disable all interrupts
  5722. mov Comm_Phase, #1
  5723. mov DPTR, #pwm_cfet
  5724. IF NFETON_DELAY == 0
  5725. mov DampingFET, #(1 SHL CpFET)
  5726. ENDIF
  5727. AnFET_off ; Turn off nfet
  5728. jnb Flags0.PWM_ON, comm61_nfet_done ; Is pwm on?
  5729. CnFET_on ; Yes - turn on nfet
  5730. comm61_nfet_done:
  5731. setb EA
  5732. Set_Comp_Phase_A ; Set comparator phase
  5733. jmp comm_exit
  5734. ; Comm6Comm1 Non-damped reverse
  5735. comm61_nondamp_rev:
  5736. clr EA ; Disable all interrupts
  5737. mov Comm_Phase, #1
  5738. mov DPTR, #pwm_afet ; (reverse)
  5739. IF NFETON_DELAY == 0
  5740. mov DampingFET, #(1 SHL ApFET)
  5741. ENDIF
  5742. CnFET_off ; Turn off nfet (reverse)
  5743. jnb Flags0.PWM_ON, comm61_nfet_done_rev ; Is pwm on?
  5744. AnFET_on ; Yes - turn on nfet (reverse)
  5745. comm61_nfet_done_rev:
  5746. setb EA
  5747. Set_Comp_Phase_C ; Set comparator phase (reverse)
  5748. comm_exit:
  5749. clr Flags0.DEMAG_CUT_POWER ; Clear demag power cut flag
  5750. ret
  5751. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5752. ;
  5753. ; Switch power off routine
  5754. ;
  5755. ; No assumptions
  5756. ;
  5757. ; Switches all fets off
  5758. ;
  5759. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5760. switch_power_off:
  5761. mov DPTR, #pwm_nofet ; Set DPTR register to pwm_nofet
  5762. mov DampingFET, #0
  5763. All_nFETs_Off ; Turn off all nfets
  5764. All_pFETs_Off ; Turn off all pfets
  5765. clr Flags0.PWM_ON ; Set pwm cycle to pwm off
  5766. ret
  5767. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5768. ;
  5769. ; Set default parameters
  5770. ;
  5771. ; No assumptions
  5772. ;
  5773. ; Sets default programming parameters
  5774. ;
  5775. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5776. set_default_parameters:
  5777. IF MODE == 0 ; Main
  5778. mov Temp1, #Pgm_Gov_P_Gain
  5779. mov @Temp1, #DEFAULT_PGM_MAIN_P_GAIN
  5780. inc Temp1
  5781. mov @Temp1, #DEFAULT_PGM_MAIN_I_GAIN
  5782. inc Temp1
  5783. mov @Temp1, #DEFAULT_PGM_MAIN_GOVERNOR_MODE
  5784. inc Temp1
  5785. mov @Temp1, #DEFAULT_PGM_MAIN_LOW_VOLTAGE_LIM
  5786. inc Temp1
  5787. mov @Temp1, #0FFh ; Motor gain
  5788. inc Temp1
  5789. mov @Temp1, #0FFh ; Motor idle
  5790. inc Temp1
  5791. mov @Temp1, #DEFAULT_PGM_MAIN_STARTUP_PWR
  5792. inc Temp1
  5793. mov @Temp1, #DEFAULT_PGM_MAIN_PWM_FREQ
  5794. inc Temp1
  5795. mov @Temp1, #DEFAULT_PGM_MAIN_DIRECTION
  5796. inc Temp1
  5797. mov @Temp1, #DEFAULT_PGM_MAIN_RCP_PWM_POL
  5798. mov Temp1, #Pgm_Enable_TX_Program
  5799. mov @Temp1, #DEFAULT_PGM_ENABLE_TX_PROGRAM
  5800. inc Temp1
  5801. mov @Temp1, #DEFAULT_PGM_MAIN_REARM_START
  5802. inc Temp1
  5803. mov @Temp1, #DEFAULT_PGM_MAIN_GOV_SETUP_TARGET
  5804. inc Temp1
  5805. mov @Temp1, #0FFh ; Startup rpm
  5806. inc Temp1
  5807. mov @Temp1, #0FFh ; Startup accel
  5808. inc Temp1
  5809. mov @Temp1, #0FFh ; Voltage comp
  5810. inc Temp1
  5811. mov @Temp1, #DEFAULT_PGM_MAIN_COMM_TIMING
  5812. inc Temp1
  5813. mov @Temp1, #0FFh ; Damping force
  5814. inc Temp1
  5815. mov @Temp1, #DEFAULT_PGM_MAIN_GOVERNOR_RANGE
  5816. inc Temp1
  5817. mov @Temp1, #0FFh ; Startup method
  5818. inc Temp1
  5819. mov @Temp1, #DEFAULT_PGM_PPM_MIN_THROTTLE
  5820. inc Temp1
  5821. mov @Temp1, #DEFAULT_PGM_PPM_MAX_THROTTLE
  5822. inc Temp1
  5823. mov @Temp1, #DEFAULT_PGM_MAIN_BEEP_STRENGTH
  5824. inc Temp1
  5825. mov @Temp1, #DEFAULT_PGM_MAIN_BEACON_STRENGTH
  5826. inc Temp1
  5827. mov @Temp1, #DEFAULT_PGM_MAIN_BEACON_DELAY
  5828. inc Temp1
  5829. mov @Temp1, #0FFh ; Throttle rate
  5830. inc Temp1
  5831. mov @Temp1, #DEFAULT_PGM_MAIN_DEMAG_COMP
  5832. inc Temp1
  5833. mov @Temp1, #DEFAULT_PGM_BEC_VOLTAGE_HIGH
  5834. inc Temp1
  5835. mov @Temp1, #DEFAULT_PGM_PPM_CENTER_THROTTLE
  5836. inc Temp1
  5837. mov @Temp1, #DEFAULT_PGM_MAIN_SPOOLUP_TIME
  5838. inc Temp1
  5839. mov @Temp1, #DEFAULT_PGM_ENABLE_TEMP_PROT
  5840. inc Temp1
  5841. mov @Temp1, #DEFAULT_PGM_ENABLE_POWER_PROT
  5842. inc Temp1
  5843. mov @Temp1, #DEFAULT_PGM_ENABLE_PWM_INPUT
  5844. inc Temp1
  5845. mov @Temp1, #0FFh ; Pwm dither
  5846. inc Temp1
  5847. mov @Temp1, #DEFAULT_PGM_BRAKE_ON_STOP
  5848. ENDIF
  5849. IF MODE == 1 ; Tail
  5850. mov Temp1, #Pgm_Gov_P_Gain
  5851. mov @Temp1, #0FFh
  5852. inc Temp1
  5853. mov @Temp1, #0FFh ; Governor I gain
  5854. inc Temp1
  5855. mov @Temp1, #0FFh ; Governor mode
  5856. inc Temp1
  5857. mov @Temp1, #0FFh ; Low voltage limit
  5858. inc Temp1
  5859. mov @Temp1, #DEFAULT_PGM_TAIL_GAIN
  5860. inc Temp1
  5861. mov @Temp1, #DEFAULT_PGM_TAIL_IDLE_SPEED
  5862. inc Temp1
  5863. mov @Temp1, #DEFAULT_PGM_TAIL_STARTUP_PWR
  5864. inc Temp1
  5865. mov @Temp1, #DEFAULT_PGM_TAIL_PWM_FREQ
  5866. inc Temp1
  5867. mov @Temp1, #DEFAULT_PGM_TAIL_DIRECTION
  5868. inc Temp1
  5869. mov @Temp1, #DEFAULT_PGM_TAIL_RCP_PWM_POL
  5870. mov Temp1, #Pgm_Enable_TX_Program
  5871. mov @Temp1, #DEFAULT_PGM_ENABLE_TX_PROGRAM
  5872. inc Temp1
  5873. mov @Temp1, #0FFh ; Main rearm start
  5874. inc Temp1
  5875. mov @Temp1, #0FFh ; Governor setup target
  5876. inc Temp1
  5877. mov @Temp1, #0FFh ; Startup rpm
  5878. inc Temp1
  5879. mov @Temp1, #0FFh ; Startup accel
  5880. inc Temp1
  5881. mov @Temp1, #0FFh ; Voltage comp
  5882. inc Temp1
  5883. mov @Temp1, #DEFAULT_PGM_TAIL_COMM_TIMING
  5884. inc Temp1
  5885. mov @Temp1, #0FFh ; Damping force
  5886. inc Temp1
  5887. mov @Temp1, #0FFh ; Governor range
  5888. inc Temp1
  5889. mov @Temp1, #0FFh ; Startup method
  5890. inc Temp1
  5891. mov @Temp1, #DEFAULT_PGM_PPM_MIN_THROTTLE
  5892. inc Temp1
  5893. mov @Temp1, #DEFAULT_PGM_PPM_MAX_THROTTLE
  5894. inc Temp1
  5895. mov @Temp1, #DEFAULT_PGM_TAIL_BEEP_STRENGTH
  5896. inc Temp1
  5897. mov @Temp1, #DEFAULT_PGM_TAIL_BEACON_STRENGTH
  5898. inc Temp1
  5899. mov @Temp1, #DEFAULT_PGM_TAIL_BEACON_DELAY
  5900. inc Temp1
  5901. mov @Temp1, #0FFh ; Throttle rate
  5902. inc Temp1
  5903. mov @Temp1, #DEFAULT_PGM_TAIL_DEMAG_COMP
  5904. inc Temp1
  5905. mov @Temp1, #DEFAULT_PGM_BEC_VOLTAGE_HIGH
  5906. inc Temp1
  5907. mov @Temp1, #DEFAULT_PGM_PPM_CENTER_THROTTLE
  5908. inc Temp1
  5909. mov @Temp1, #0FFh
  5910. inc Temp1
  5911. mov @Temp1, #DEFAULT_PGM_ENABLE_TEMP_PROT
  5912. inc Temp1
  5913. mov @Temp1, #DEFAULT_PGM_ENABLE_POWER_PROT
  5914. inc Temp1
  5915. mov @Temp1, #DEFAULT_PGM_ENABLE_PWM_INPUT
  5916. inc Temp1
  5917. mov @Temp1, #DEFAULT_PGM_TAIL_PWM_DITHER
  5918. inc Temp1
  5919. mov @Temp1, #DEFAULT_PGM_BRAKE_ON_STOP
  5920. ENDIF
  5921. IF MODE == 2 ; Multi
  5922. mov Temp1, #Pgm_Gov_P_Gain
  5923. mov @Temp1, #DEFAULT_PGM_MULTI_P_GAIN
  5924. inc Temp1
  5925. mov @Temp1, #DEFAULT_PGM_MULTI_I_GAIN
  5926. inc Temp1
  5927. mov @Temp1, #DEFAULT_PGM_MULTI_GOVERNOR_MODE
  5928. inc Temp1
  5929. mov @Temp1, #0FFh ; Low voltage limit
  5930. inc Temp1
  5931. mov @Temp1, #DEFAULT_PGM_MULTI_GAIN
  5932. inc Temp1
  5933. mov @Temp1, #0FFh
  5934. inc Temp1
  5935. mov @Temp1, #DEFAULT_PGM_MULTI_STARTUP_PWR
  5936. inc Temp1
  5937. mov @Temp1, #DEFAULT_PGM_MULTI_PWM_FREQ
  5938. inc Temp1
  5939. mov @Temp1, #DEFAULT_PGM_MULTI_DIRECTION
  5940. inc Temp1
  5941. mov @Temp1, #DEFAULT_PGM_MULTI_RCP_PWM_POL
  5942. mov Temp1, #Pgm_Enable_TX_Program
  5943. mov @Temp1, #DEFAULT_PGM_ENABLE_TX_PROGRAM
  5944. inc Temp1
  5945. mov @Temp1, #0FFh ; Main rearm start
  5946. inc Temp1
  5947. mov @Temp1, #0FFh ; Governor setup target
  5948. inc Temp1
  5949. mov @Temp1, #0FFh ; Startup rpm
  5950. inc Temp1
  5951. mov @Temp1, #0FFh ; Startup accel
  5952. inc Temp1
  5953. mov @Temp1, #0FFh ; Voltage comp
  5954. inc Temp1
  5955. mov @Temp1, #DEFAULT_PGM_MULTI_COMM_TIMING
  5956. inc Temp1
  5957. mov @Temp1, #0FFh ; Damping force
  5958. inc Temp1
  5959. mov @Temp1, #0FFh ; Governor range
  5960. inc Temp1
  5961. mov @Temp1, #0FFh ; Startup method
  5962. inc Temp1
  5963. mov @Temp1, #DEFAULT_PGM_PPM_MIN_THROTTLE
  5964. inc Temp1
  5965. mov @Temp1, #DEFAULT_PGM_PPM_MAX_THROTTLE
  5966. inc Temp1
  5967. mov @Temp1, #DEFAULT_PGM_MULTI_BEEP_STRENGTH
  5968. inc Temp1
  5969. mov @Temp1, #DEFAULT_PGM_MULTI_BEACON_STRENGTH
  5970. inc Temp1
  5971. mov @Temp1, #DEFAULT_PGM_MULTI_BEACON_DELAY
  5972. inc Temp1
  5973. mov @Temp1, #0FFh ; Throttle rate
  5974. inc Temp1
  5975. mov @Temp1, #DEFAULT_PGM_MULTI_DEMAG_COMP
  5976. inc Temp1
  5977. mov @Temp1, #DEFAULT_PGM_BEC_VOLTAGE_HIGH
  5978. inc Temp1
  5979. mov @Temp1, #DEFAULT_PGM_PPM_CENTER_THROTTLE
  5980. inc Temp1
  5981. mov @Temp1, #0FFh
  5982. inc Temp1
  5983. mov @Temp1, #DEFAULT_PGM_ENABLE_TEMP_PROT
  5984. inc Temp1
  5985. mov @Temp1, #DEFAULT_PGM_ENABLE_POWER_PROT
  5986. inc Temp1
  5987. mov @Temp1, #DEFAULT_PGM_ENABLE_PWM_INPUT
  5988. inc Temp1
  5989. mov @Temp1, #DEFAULT_PGM_MULTI_PWM_DITHER
  5990. inc Temp1
  5991. mov @Temp1, #DEFAULT_PGM_BRAKE_ON_STOP
  5992. ENDIF
  5993. ret
  5994. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  5995. ;
  5996. ; Decode parameters
  5997. ;
  5998. ; No assumptions
  5999. ;
  6000. ; Decodes programming parameters
  6001. ;
  6002. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  6003. decode_parameters:
  6004. ; Load programmed pwm frequency
  6005. mov Temp1, #Pgm_Pwm_Freq ; Load pwm freq
  6006. mov A, @Temp1
  6007. mov Temp8, A ; Store in Temp8
  6008. clr Flags2.PGM_PWMOFF_DAMPED
  6009. IF DAMPED_MODE_ENABLE == 1
  6010. cjne Temp8, #3, ($+5)
  6011. setb Flags2.PGM_PWMOFF_DAMPED
  6012. ENDIF
  6013. ; Load programmed direction
  6014. mov Temp1, #Pgm_Direction
  6015. IF MODE >= 1 ; Tail or multi
  6016. mov A, @Temp1
  6017. clr C
  6018. subb A, #3
  6019. jz decode_params_dir_set
  6020. ENDIF
  6021. clr Flags3.PGM_DIR_REV
  6022. mov A, @Temp1
  6023. jnb ACC.1, ($+5)
  6024. setb Flags3.PGM_DIR_REV
  6025. decode_params_dir_set:
  6026. clr Flags3.PGM_RCP_PWM_POL
  6027. mov Temp1, #Pgm_Input_Pol
  6028. mov A, @Temp1
  6029. jnb ACC.1, ($+5)
  6030. setb Flags3.PGM_RCP_PWM_POL
  6031. clr C
  6032. mov A, Temp8
  6033. subb A, #2
  6034. jz decode_pwm_freq_low
  6035. mov CKCON, #01h ; Timer0 set for clk/4 (22kHz pwm)
  6036. setb Flags2.PGM_PWM_HIGH_FREQ
  6037. jmp decode_pwm_freq_end
  6038. decode_pwm_freq_low:
  6039. mov CKCON, #00h ; Timer0 set for clk/12 (8kHz pwm)
  6040. clr Flags2.PGM_PWM_HIGH_FREQ
  6041. decode_pwm_freq_end:
  6042. ret
  6043. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  6044. ;
  6045. ; Decode settings
  6046. ;
  6047. ; No assumptions
  6048. ;
  6049. ; Decodes various settings
  6050. ;
  6051. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  6052. decode_settings:
  6053. ; Decode governor gains
  6054. mov Temp1, #Pgm_Gov_P_Gain ; Decode governor P gain
  6055. mov A, @Temp1
  6056. dec A
  6057. mov DPTR, #GOV_GAIN_TABLE
  6058. movc A, @A+DPTR
  6059. mov Temp1, #Pgm_Gov_P_Gain_Decoded
  6060. mov @Temp1, A
  6061. mov Temp1, #Pgm_Gov_I_Gain ; Decode governor I gain
  6062. mov A, @Temp1
  6063. dec A
  6064. mov DPTR, #GOV_GAIN_TABLE
  6065. movc A, @A+DPTR
  6066. mov Temp1, #Pgm_Gov_I_Gain_Decoded
  6067. mov @Temp1, A
  6068. ; Decode startup power
  6069. mov Temp1, #Pgm_Startup_Pwr
  6070. mov A, @Temp1
  6071. dec A
  6072. mov DPTR, #STARTUP_POWER_TABLE
  6073. movc A, @A+DPTR
  6074. mov Temp1, #Pgm_Startup_Pwr_Decoded
  6075. mov @Temp1, A
  6076. IF MODE == 0 ; Main
  6077. ; Decode spoolup time
  6078. mov Temp1, #Pgm_Main_Spoolup_Time
  6079. mov A, @Temp1
  6080. mov Temp1, A ; Store
  6081. jnz decode_main_spoolup_nonzero ; If not zero - branch
  6082. mov Main_Spoolup_Time_3x, #0
  6083. ajmp decode_main_spoolup_done
  6084. decode_main_spoolup_nonzero:
  6085. clr C
  6086. mov A, Temp1
  6087. subb A, #17 ; Limit to 17 max
  6088. jc ($+4)
  6089. mov Temp1, #17
  6090. mov A, Temp1
  6091. add A, Temp1
  6092. add A, Temp1 ; Now 3x
  6093. mov Main_Spoolup_Time_3x, A
  6094. add A, Main_Spoolup_Time_3x
  6095. add A, Main_Spoolup_Time_3x
  6096. add A, Temp1 ; Now 10x
  6097. mov Main_Spoolup_Time_10x, A
  6098. add A, Main_Spoolup_Time_3x
  6099. add A, Temp1
  6100. add A, Temp1 ; Now 15x
  6101. mov Main_Spoolup_Time_15x, A
  6102. decode_main_spoolup_done:
  6103. ENDIF
  6104. ; Decode low rpm power slope
  6105. mov Temp1, #Pgm_Startup_Pwr
  6106. mov A, @Temp1
  6107. mov Low_Rpm_Pwr_Slope, A
  6108. clr C
  6109. subb A, #2
  6110. jnc ($+5)
  6111. mov Low_Rpm_Pwr_Slope, #2
  6112. ; Decode demag compensation
  6113. mov Temp1, #Pgm_Demag_Comp
  6114. mov A, @Temp1
  6115. mov Demag_Pwr_Off_Thresh, #255 ; Set default
  6116. cjne A, #2, decode_demag_high
  6117. mov Demag_Pwr_Off_Thresh, #160 ; Settings for demag comp low
  6118. decode_demag_high:
  6119. cjne A, #3, decode_demag_done
  6120. mov Demag_Pwr_Off_Thresh, #130 ; Settings for demag comp high
  6121. decode_demag_done:
  6122. ; Decode pwm dither
  6123. mov Temp1, #Pgm_Pwm_Dither
  6124. mov A, @Temp1
  6125. dec A
  6126. mov DPTR, #PWM_DITHER_TABLE
  6127. movc A, @A+DPTR
  6128. mov Pwm_Dither_Decoded, A
  6129. call switch_power_off ; Reset DPTR
  6130. ret
  6131. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  6132. ;
  6133. ; Set BEC voltage
  6134. ;
  6135. ; No assumptions
  6136. ;
  6137. ; Sets the BEC output voltage low or high
  6138. ;
  6139. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  6140. set_bec_voltage:
  6141. ; Set bec voltage
  6142. IF HIGH_BEC_VOLTAGE == 1
  6143. Set_BEC_Lo ; Set default to low
  6144. mov Temp1, #Pgm_BEC_Voltage_High
  6145. mov A, @Temp1
  6146. jz set_bec_voltage_exit
  6147. Set_BEC_Hi ; Set to high
  6148. set_bec_voltage_exit:
  6149. ENDIF
  6150. IF HIGH_BEC_VOLTAGE == 2
  6151. Set_BEC_0 ; Set default to low
  6152. mov Temp1, #Pgm_BEC_Voltage_High
  6153. mov A, @Temp1
  6154. cjne A, #1, set_bec_voltage_2
  6155. Set_BEC_1 ; Set to level 1
  6156. set_bec_voltage_2:
  6157. cjne A, #2, set_bec_voltage_exit
  6158. Set_BEC_2 ; Set to level 2
  6159. set_bec_voltage_exit:
  6160. ENDIF
  6161. ret
  6162. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  6163. ;
  6164. ; Find throttle gain
  6165. ;
  6166. ; The difference between max and min throttle must be more than 520us (a Pgm_Ppm_xxx_Throttle difference of 130)
  6167. ;
  6168. ; Finds throttle gain from throttle calibration values
  6169. ;
  6170. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  6171. find_throttle_gain:
  6172. ; Load programmed minimum and maximum throttle
  6173. mov Temp1, #Pgm_Ppm_Min_Throttle
  6174. mov A, @Temp1
  6175. mov Temp3, A
  6176. mov Temp1, #Pgm_Ppm_Max_Throttle
  6177. mov A, @Temp1
  6178. mov Temp4, A
  6179. mov Temp1, #Pgm_Direction ; Check if bidirectional operation
  6180. mov A, @Temp1
  6181. cjne A, #3, find_throttle_gain_check_full
  6182. clr C
  6183. mov A, Temp4
  6184. subb A, #14 ; Compensate for higher deadband in bidirectional
  6185. mov Temp4, A
  6186. find_throttle_gain_check_full:
  6187. ; Check if full range is chosen
  6188. jnb Flags3.FULL_THROTTLE_RANGE, find_throttle_gain_calculate
  6189. mov Temp3, #0
  6190. mov Temp4, #255
  6191. find_throttle_gain_calculate:
  6192. ; Calculate difference
  6193. clr C
  6194. mov A, Temp4
  6195. subb A, Temp3
  6196. mov Temp5, A
  6197. ; Check that difference is minimum 130
  6198. clr C
  6199. subb A, #130
  6200. jnc ($+4)
  6201. mov Temp5, #130
  6202. ; Find gain
  6203. mov Ppm_Throttle_Gain, #0
  6204. test_throttle_gain:
  6205. inc Ppm_Throttle_Gain
  6206. mov A, Temp5
  6207. mov B, Ppm_Throttle_Gain ; A has difference, B has gain
  6208. mul AB
  6209. clr C
  6210. mov A, B
  6211. subb A, #125
  6212. jc test_throttle_gain
  6213. ret
  6214. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  6215. ;
  6216. ; Average throttle
  6217. ;
  6218. ; Outputs result in Temp7
  6219. ;
  6220. ; Averages throttle calibration readings
  6221. ;
  6222. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  6223. average_throttle:
  6224. setb Flags3.FULL_THROTTLE_RANGE ; Set range to 1000-2020us
  6225. call find_throttle_gain ; Set throttle gain
  6226. call wait30ms
  6227. call wait30ms
  6228. mov Temp3, #0
  6229. mov Temp4, #0
  6230. mov Temp5, #16 ; Average 16 measurments
  6231. average_throttle_meas:
  6232. call wait3ms ; Wait for new RC pulse value
  6233. mov A, New_Rcp ; Get new RC pulse value
  6234. add A, Temp3
  6235. mov Temp3, A
  6236. mov A, #0
  6237. addc A, Temp4
  6238. mov Temp4, A
  6239. djnz Temp5, average_throttle_meas
  6240. mov Temp5, #4 ; Shift 4 times
  6241. average_throttle_div:
  6242. clr C
  6243. mov A, Temp4 ; Shift right
  6244. rrc A
  6245. mov Temp4, A
  6246. mov A, Temp3
  6247. rrc A
  6248. mov Temp3, A
  6249. djnz Temp5, average_throttle_div
  6250. mov Temp7, A ; Copy to Temp7
  6251. clr Flags3.FULL_THROTTLE_RANGE
  6252. call find_throttle_gain ; Set throttle gain
  6253. ret
  6254. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  6255. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  6256. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  6257. ;
  6258. ; Main program start
  6259. ;
  6260. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  6261. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  6262. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  6263. pgm_start:
  6264. ; Initialize flash keys to invalid values
  6265. mov Flash_Key_1, #0
  6266. mov Flash_Key_2, #0
  6267. ; Check flash lock byte
  6268. mov A, RSTSRC
  6269. jb ACC.6, ($+6) ; Check if flash access error was reset source
  6270. mov Bit_Access, #0 ; No - then this is the first try
  6271. inc Bit_Access
  6272. mov DPTR, #LOCK_BYTE_ADDRESS_16K ; First try is for 16k flash size
  6273. mov A, Bit_Access
  6274. dec A
  6275. jz lock_byte_test
  6276. mov DPTR, #LOCK_BYTE_ADDRESS_8K ; Second try is for 8k flash size
  6277. dec A
  6278. jz lock_byte_test
  6279. lock_byte_test:
  6280. movc A, @A+DPTR ; Read lock byte
  6281. inc A
  6282. jz lock_byte_ok ; If lock byte is 0xFF, then start code execution
  6283. IF ONE_S_CAPABLE == 0
  6284. mov RSTSRC, #16h ; Generate hardware reset and set missing clock and VDD monitor
  6285. ELSE
  6286. mov RSTSRC, #14h ; Generate hardware reset and disable VDD monitor
  6287. ENDIF
  6288. lock_byte_ok:
  6289. ; Disable the WDT.
  6290. IF SIGNATURE_001 == 0f3h
  6291. anl PCA0MD, #NOT(40h) ; Clear watchdog enable bit
  6292. ENDIF
  6293. IF SIGNATURE_001 == 0f8h
  6294. mov WDTCN, #0DEh ; Disable watchdog
  6295. mov WDTCN, #0ADh
  6296. ENDIF
  6297. ; Initialize stack
  6298. mov SP, #0c0h ; Stack = 64 upper bytes of RAM
  6299. ; Initialize VDD monitor
  6300. orl VDM0CN, #080h ; Enable the VDD monitor
  6301. call wait1ms ; Wait at least 100us
  6302. IF ONE_S_CAPABLE == 0
  6303. mov RSTSRC, #06h ; Set missing clock and VDD monitor as a reset source if not 1S capable
  6304. ELSE
  6305. mov RSTSRC, #04h ; Do not set VDD monitor as a reset source for 1S ESCSs, in order to avoid resets due to it
  6306. ENDIF
  6307. ; Set clock frequency
  6308. IF SIGNATURE_001 == 0f3h
  6309. orl OSCICN, #03h ; Set clock divider to 1 (not supported on 'f850)
  6310. ENDIF
  6311. IF SIGNATURE_001 == 0f8h
  6312. mov CLKSEL, #00h ; Set clock divider to 1 (not supported on 'f3xx)
  6313. ENDIF
  6314. mov A, OSCICL
  6315. add A, #02h ; 24.5MHz to 24MHz (~0.5-1% per step)
  6316. jb ACC.7, reset_cal_done ; Is carry (7bit) set? - branch
  6317. mov Bit_Access_Int, A
  6318. IF SIGNATURE_002 <> 010h
  6319. mov A, OSCLCN
  6320. ELSE
  6321. mov A, OSCXCN
  6322. ENDIF
  6323. jb ACC.0, reset_cal_done ; Set if cal aleady done
  6324. mov OSCICL, Bit_Access_Int
  6325. IF SIGNATURE_002 <> 010h
  6326. orl OSCLCN, #01h ; Tag that cal is done
  6327. ELSE
  6328. orl OSCXCN, #01h ; Tag that cal is done
  6329. ENDIF
  6330. reset_cal_done:
  6331. ; Switch power off
  6332. call switch_power_off
  6333. ; Ports initialization
  6334. mov P0, #P0_INIT
  6335. mov P0MDOUT, #P0_PUSHPULL
  6336. mov P0MDIN, #P0_DIGITAL
  6337. mov P0SKIP, #P0_SKIP
  6338. mov P1, #P1_INIT
  6339. mov P1MDOUT, #P1_PUSHPULL
  6340. mov P1MDIN, #P1_DIGITAL
  6341. mov P1SKIP, #P1_SKIP
  6342. IF PORT3_EXIST == 1
  6343. mov P2, #P2_INIT
  6344. ENDIF
  6345. mov P2MDOUT, #P2_PUSHPULL
  6346. IF PORT3_EXIST == 1
  6347. mov P2MDIN, #P2_DIGITAL
  6348. mov P2SKIP, #P2_SKIP
  6349. mov P3, #P3_INIT
  6350. mov P3MDOUT, #P3_PUSHPULL
  6351. mov P3MDIN, #P3_DIGITAL
  6352. ENDIF
  6353. ; Initialize the XBAR and related functionality
  6354. Initialize_Xbar
  6355. ; Switch power off again, after initializing ports
  6356. call switch_power_off
  6357. ; Clear RAM
  6358. clr A ; Clear accumulator
  6359. mov Temp1, A ; Clear Temp1
  6360. clear_ram:
  6361. mov @Temp1, A ; Clear RAM
  6362. djnz Temp1, clear_ram ; Is A not zero? - jump
  6363. ; Initialize LFSR
  6364. mov Random, #1
  6365. ; Set default programmed parameters
  6366. call set_default_parameters
  6367. ; Read all programmed parameters
  6368. call read_all_eeprom_parameters
  6369. ; Set beep strength
  6370. mov Temp1, #Pgm_Beep_Strength
  6371. mov Beep_Strength, @Temp1
  6372. ; Set initial arm variable
  6373. mov Initial_Arm, #1
  6374. ; Initializing beep
  6375. clr EA ; Disable interrupts explicitly
  6376. call wait200ms
  6377. call beep_f1
  6378. call wait30ms
  6379. call beep_f2
  6380. call wait30ms
  6381. call beep_f3
  6382. call wait30ms
  6383. IF MODE <= 1 ; Main or tail
  6384. ; Wait for receiver to initialize
  6385. call wait1s
  6386. call wait200ms
  6387. call wait200ms
  6388. call wait100ms
  6389. ENDIF
  6390. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  6391. ;
  6392. ; No signal entry point
  6393. ;
  6394. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  6395. init_no_signal:
  6396. ; Disable interrupts explicitly
  6397. clr EA
  6398. ; Initialize flash keys to invalid values
  6399. mov Flash_Key_1, #0
  6400. mov Flash_Key_2, #0
  6401. ; Check if input signal is high for more than 15ms
  6402. mov Temp1, #250
  6403. input_high_check_1:
  6404. mov Temp2, #250
  6405. input_high_check_2:
  6406. jnb RTX_PORT.RTX_PIN, bootloader_done ; Look for low
  6407. djnz Temp2, input_high_check_2
  6408. djnz Temp1, input_high_check_1
  6409. ljmp 1C00h ; Jump to bootloader
  6410. bootloader_done:
  6411. ; Decode parameters
  6412. call decode_parameters
  6413. ; Decode settings
  6414. call decode_settings
  6415. ; Set BEC voltage
  6416. call set_bec_voltage
  6417. ; Find throttle gain from stored min and max settings
  6418. call find_throttle_gain
  6419. ; Set beep strength
  6420. mov Temp1, #Pgm_Beep_Strength
  6421. mov Beep_Strength, @Temp1
  6422. ; Switch power off
  6423. call switch_power_off
  6424. ; Set clock frequency
  6425. IF MCU_48MHZ == 1
  6426. Set_MCU_Clk_24MHz
  6427. ENDIF
  6428. ; Timer control
  6429. mov TCON, #10h ; Timer0 enabled
  6430. ; Timer mode
  6431. mov TMOD, #02h ; Timer0 as 8bit
  6432. ; Timer2: clk/12 for 128us and 32ms interrupts
  6433. mov TMR2CN, #24h ; Timer2 enabled, low counter interrups enabled
  6434. ; Timer3: clk/12 for commutation timing
  6435. mov TMR3CN, #04h ; Timer3 enabled
  6436. ; PCA
  6437. mov PCA0CN, #40h ; PCA enabled
  6438. ; Enable interrupts
  6439. mov IE, #22h ; Enable timer0 and timer2 interrupts
  6440. mov IP, #02h ; High priority to timer0 interrupts
  6441. mov EIE1, #90h ; Enable timer3 and PCA0 interrupts
  6442. ; Initialize comparator
  6443. mov CPT0CN, #80h ; Comparator enabled, no hysteresis
  6444. mov CPT0MD, #00h ; Comparator response time 100ns
  6445. IF COMP1_USED == 1
  6446. mov CPT1CN, #80h ; Comparator enabled, no hysteresis
  6447. mov CPT1MD, #00h ; Comparator response time 100ns
  6448. ENDIF
  6449. ; Initialize ADC
  6450. Initialize_Adc ; Initialize ADC operation
  6451. call wait1ms
  6452. setb EA ; Enable all interrupts
  6453. ; Measure number of lipo cells
  6454. call Measure_Lipo_Cells ; Measure number of lipo cells
  6455. ; Reset stall count
  6456. mov Stall_Cnt, #0
  6457. ; Initialize RC pulse
  6458. Rcp_Int_First ; Enable interrupt and set to first edge
  6459. Rcp_Int_Enable ; Enable interrupt
  6460. Rcp_Clear_Int_Flag ; Clear interrupt flag
  6461. clr Flags2.RCP_EDGE_NO ; Set first edge flag
  6462. call wait200ms
  6463. ; Measure PWM frequency
  6464. measure_pwm_freq_init:
  6465. setb Flags0.RCP_MEAS_PWM_FREQ ; Set measure pwm frequency flag
  6466. mov Temp4, #3 ; Number of attempts before going back to detect input signal
  6467. measure_pwm_freq_start:
  6468. mov Temp3, #12 ; Number of pulses to measure
  6469. measure_pwm_freq_loop:
  6470. ; Check if period diff was accepted
  6471. mov A, Rcp_Period_Diff_Accepted
  6472. jnz measure_pwm_freq_wait
  6473. mov Temp3, #12 ; Reset number of pulses to measure
  6474. djnz Temp4, ($+5) ; If it is not zero - proceed
  6475. ljmp init_no_signal ; Go back to detect input signal
  6476. measure_pwm_freq_wait:
  6477. call wait30ms ; Wait 30ms for new pulse
  6478. jb Flags2.RCP_UPDATED, ($+6) ; Is there an updated RC pulse available - proceed
  6479. ljmp init_no_signal ; Go back to detect input signal
  6480. clr Flags2.RCP_UPDATED ; Flag that pulse has been evaluated
  6481. mov A, New_Rcp ; Load value
  6482. clr C
  6483. subb A, #RCP_VALIDATE ; Higher than validate level?
  6484. jc measure_pwm_freq_start ; No - start over
  6485. mov A, Flags3 ; Check pwm frequency flags
  6486. 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))
  6487. mov Prev_Rcp_Pwm_Freq, Curr_Rcp_Pwm_Freq ; Store as previous flags for next pulse
  6488. mov Curr_Rcp_Pwm_Freq, A ; Store current flags for next pulse
  6489. cjne A, Prev_Rcp_Pwm_Freq, measure_pwm_freq_start ; Go back if new flags not same as previous
  6490. djnz Temp3, measure_pwm_freq_loop ; Go back if not required number of pulses seen
  6491. ; Clear measure pwm frequency flag
  6492. clr Flags0.RCP_MEAS_PWM_FREQ
  6493. ; Set up RC pulse interrupts after pwm frequency measurement
  6494. Rcp_Int_First ; Enable interrupt and set to first edge
  6495. Rcp_Clear_Int_Flag ; Clear interrupt flag
  6496. clr Flags2.RCP_EDGE_NO ; Set first edge flag
  6497. mov Temp1, #Pgm_Enable_PWM_Input ; Check if PWM input is enabled
  6498. mov A, @Temp1
  6499. jnz test_for_oneshot ; If it is - proceed
  6500. setb Flags2.RCP_PPM ; Set PPM flag
  6501. mov A, Flags3 ; Clear pwm frequency flags
  6502. anl A, #NOT((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))
  6503. mov Flags3, A
  6504. test_for_oneshot:
  6505. ; Test whether signal is OneShot125
  6506. clr Flags2.RCP_PPM_ONESHOT125 ; Clear OneShot125 flag
  6507. mov Rcp_Outside_Range_Cnt, #0 ; Reset out of range counter
  6508. call wait100ms ; Wait for new RC pulse
  6509. jnb Flags2.RCP_PPM, validate_rcp_start ; If flag is not set (PWM) - branch
  6510. clr C
  6511. mov A, Rcp_Outside_Range_Cnt ; Check how many pulses were outside normal PPM range (800-2160us)
  6512. subb A, #10
  6513. jc validate_rcp_start
  6514. setb Flags2.RCP_PPM_ONESHOT125 ; Set OneShot125 flag
  6515. ; Validate RC pulse
  6516. validate_rcp_start:
  6517. call wait3ms ; Wait for next pulse (NB: Uses Temp1/2!)
  6518. mov Temp1, #RCP_VALIDATE ; Set validate level as default
  6519. jnb Flags2.RCP_PPM, ($+5) ; If flag is not set (PWM) - branch
  6520. mov Temp1, #0 ; Set level to zero for PPM (any level will be accepted)
  6521. clr C
  6522. mov A, New_Rcp ; Load value
  6523. subb A, Temp1 ; Higher than validate level?
  6524. jc validate_rcp_start ; No - start over
  6525. ; Beep arm sequence start signal
  6526. clr EA ; Disable all interrupts
  6527. call beep_f1 ; Signal that RC pulse is ready
  6528. call beep_f1
  6529. call beep_f1
  6530. setb EA ; Enable all interrupts
  6531. call wait200ms
  6532. ; Arming sequence start
  6533. mov Gov_Arm_Target, #0 ; Clear governor arm target
  6534. arming_start:
  6535. IF MODE >= 1 ; Tail or multi
  6536. mov Temp1, #Pgm_Direction ; Check if bidirectional operation
  6537. mov A, @Temp1
  6538. cjne A, #3, ($+5)
  6539. ajmp program_by_tx_checked ; Disable tx programming if bidirectional operation
  6540. ENDIF
  6541. call wait3ms
  6542. mov Temp1, #Pgm_Enable_TX_Program; Start programming mode entry if enabled
  6543. mov A, @Temp1
  6544. clr C
  6545. subb A, #1 ; Is TX programming enabled?
  6546. jnc arming_initial_arm_check ; Yes - proceed
  6547. jmp program_by_tx_checked ; No - branch
  6548. arming_initial_arm_check:
  6549. mov A, Initial_Arm ; Yes - check if it is initial arm sequence
  6550. clr C
  6551. subb A, #1 ; Is it the initial arm sequence?
  6552. jnc arming_ppm_check ; Yes - proceed
  6553. jmp program_by_tx_checked ; No - branch
  6554. arming_ppm_check:
  6555. ; Initialize flash keys to valid values
  6556. mov Flash_Key_1, #0A5h
  6557. mov Flash_Key_2, #0F1h
  6558. jb Flags2.RCP_PPM, throttle_high_cal_start ; If flag is set (PPM) - branch
  6559. ; PWM tx program entry
  6560. clr C
  6561. mov A, New_Rcp ; Load new RC pulse value
  6562. subb A, #RCP_MAX ; Is RC pulse max?
  6563. jnc program_by_tx_entry_pwm ; Yes - proceed
  6564. jmp program_by_tx_checked ; No - branch
  6565. program_by_tx_entry_pwm:
  6566. clr EA ; Disable all interrupts
  6567. call beep_f4
  6568. setb EA ; Enable all interrupts
  6569. call wait100ms
  6570. clr C
  6571. mov A, New_Rcp ; Load new RC pulse value
  6572. subb A, #RCP_STOP ; Below stop?
  6573. jnc program_by_tx_entry_pwm ; No - start over
  6574. program_by_tx_entry_wait_pwm:
  6575. clr EA ; Disable all interrupts
  6576. call beep_f1
  6577. call wait10ms
  6578. call beep_f1
  6579. setb EA ; Enable all interrupts
  6580. call wait100ms
  6581. clr C
  6582. mov A, New_Rcp ; Load new RC pulse value
  6583. subb A, #RCP_MAX ; At or above max?
  6584. jc program_by_tx_entry_wait_pwm ; No - start over
  6585. jmp program_by_tx ; Yes - enter programming mode
  6586. ; PPM throttle calibration and tx program entry
  6587. throttle_high_cal_start:
  6588. IF MODE <= 1 ; Main or tail
  6589. mov Temp8, #5 ; Set 3 seconds wait time
  6590. ELSE
  6591. mov Temp8, #2 ; Set 1 seconds wait time
  6592. ENDIF
  6593. throttle_high_cal:
  6594. setb Flags3.FULL_THROTTLE_RANGE ; Set range to 1000-2020us
  6595. call find_throttle_gain ; Set throttle gain
  6596. call wait100ms ; Wait for new throttle value
  6597. clr EA ; Disable interrupts (freeze New_Rcp value)
  6598. clr Flags3.FULL_THROTTLE_RANGE ; Set programmed range
  6599. call find_throttle_gain ; Set throttle gain
  6600. mov Temp7, New_Rcp ; Store new RC pulse value
  6601. clr C
  6602. mov A, New_Rcp ; Load new RC pulse value
  6603. subb A, #(RCP_MAX/2) ; Is RC pulse above midstick?
  6604. setb EA ; Enable interrupts
  6605. jnc ($+4)
  6606. ajmp arm_target_updated ; No - branch
  6607. call wait1ms
  6608. clr EA ; Disable all interrupts
  6609. call beep_f4
  6610. setb EA ; Enable all interrupts
  6611. djnz Temp8, throttle_high_cal ; Continue to wait
  6612. call average_throttle
  6613. clr C
  6614. mov A, Temp7
  6615. IF MODE <= 1 ; Main or tail
  6616. subb A, #5 ; Subtract about 2% and ensure that it is 250 or lower
  6617. ENDIF
  6618. mov Temp1, #Pgm_Ppm_Max_Throttle ; Store
  6619. mov @Temp1, A
  6620. call wait200ms
  6621. call success_beep
  6622. throttle_low_cal_start:
  6623. mov Temp8, #10 ; Set 3 seconds wait time
  6624. throttle_low_cal:
  6625. setb Flags3.FULL_THROTTLE_RANGE ; Set range to 1000-2020us
  6626. call find_throttle_gain ; Set throttle gain
  6627. call wait100ms
  6628. clr EA ; Disable interrupts (freeze New_Rcp value)
  6629. clr Flags3.FULL_THROTTLE_RANGE ; Set programmed range
  6630. call find_throttle_gain ; Set throttle gain
  6631. mov Temp7, New_Rcp ; Store new RC pulse value
  6632. clr C
  6633. mov A, New_Rcp ; Load new RC pulse value
  6634. subb A, #(RCP_MAX/2) ; Below midstick?
  6635. setb EA ; Enable interrupts
  6636. jnc throttle_low_cal_start ; No - start over
  6637. call wait1ms
  6638. clr EA ; Disable all interrupts
  6639. call beep_f1
  6640. call wait10ms
  6641. call beep_f1
  6642. setb EA ; Enable all interrupts
  6643. djnz Temp8, throttle_low_cal ; Continue to wait
  6644. call average_throttle
  6645. mov A, Temp7
  6646. add A, #3 ; Add about 1%
  6647. mov Temp1, #Pgm_Ppm_Min_Throttle ; Store
  6648. mov @Temp1, A
  6649. mov Temp1, A ; Min throttle in Temp1
  6650. mov Temp2, #Pgm_Ppm_Max_Throttle
  6651. mov A, @Temp2
  6652. clr C
  6653. subb A, #130 ; Subtract 130 (520us) from max throttle
  6654. jc program_by_tx_entry_limit
  6655. subb A, Temp1 ; Subtract min from max
  6656. jnc program_by_tx_entry_store
  6657. program_by_tx_entry_limit:
  6658. mov A, Temp1 ; Load min
  6659. add A, #130 ; Make max 520us higher than min
  6660. mov Temp1, #Pgm_Ppm_Max_Throttle ; Store new max
  6661. mov @Temp1, A
  6662. program_by_tx_entry_store:
  6663. call wait200ms
  6664. call erase_and_store_all_in_eeprom
  6665. call success_beep_inverted
  6666. program_by_tx_entry_wait_ppm:
  6667. call wait100ms
  6668. call find_throttle_gain ; Set throttle gain
  6669. clr C
  6670. mov A, New_Rcp ; Load new RC pulse value
  6671. subb A, #RCP_MAX ; At or above max?
  6672. jnc ($+4)
  6673. ajmp arming_ppm_check ; No - go back
  6674. jmp program_by_tx ; Yes - enter programming mode
  6675. program_by_tx_checked:
  6676. ; Initialize flash keys to invalid values
  6677. mov Flash_Key_1, #0
  6678. mov Flash_Key_2, #0
  6679. clr C
  6680. mov A, New_Rcp ; Load new RC pulse value
  6681. subb A, Gov_Arm_Target ; Is RC pulse larger than arm target?
  6682. jc arm_target_updated ; No - do not update
  6683. mov Gov_Arm_Target, New_Rcp ; Yes - update arm target
  6684. arm_target_updated:
  6685. call wait100ms ; Wait for new throttle value
  6686. mov Temp1, #RCP_STOP ; Default stop value
  6687. mov Temp2, #Pgm_Direction ; Check if bidirectional operation
  6688. mov A, @Temp2
  6689. cjne A, #3, ($+5) ; No - branch
  6690. mov Temp1, #(RCP_STOP+4) ; Higher stop value for bidirectional
  6691. clr C
  6692. mov A, New_Rcp ; Load new RC pulse value
  6693. subb A, Temp1 ; Below stop?
  6694. jc arm_end_beep ; Yes - proceed
  6695. jmp arming_start ; No - start over
  6696. arm_end_beep:
  6697. ; Beep arm sequence end signal
  6698. clr EA ; Disable all interrupts
  6699. call beep_f4 ; Signal that rcpulse is ready
  6700. call beep_f4
  6701. call beep_f4
  6702. setb EA ; Enable all interrupts
  6703. call wait200ms
  6704. ; Clear initial arm variable
  6705. mov Initial_Arm, #0
  6706. ; Armed and waiting for power on
  6707. wait_for_power_on:
  6708. clr A
  6709. mov Power_On_Wait_Cnt_L, A ; Clear wait counter
  6710. mov Power_On_Wait_Cnt_H, A
  6711. wait_for_power_on_loop:
  6712. inc Power_On_Wait_Cnt_L ; Increment low wait counter
  6713. mov A, Power_On_Wait_Cnt_L
  6714. cpl A
  6715. jnz wait_for_power_on_no_beep; Counter wrapping (about 3 sec)
  6716. inc Power_On_Wait_Cnt_H ; Increment high wait counter
  6717. mov Temp1, #Pgm_Beacon_Delay
  6718. mov A, @Temp1
  6719. mov Temp1, #25 ; Approximately 1 min
  6720. dec A
  6721. jz beep_delay_set
  6722. mov Temp1, #50 ; Approximately 2 min
  6723. dec A
  6724. jz beep_delay_set
  6725. mov Temp1, #125 ; Approximately 5 min
  6726. dec A
  6727. jz beep_delay_set
  6728. mov Temp1, #250 ; Approximately 10 min
  6729. dec A
  6730. jz beep_delay_set
  6731. mov Power_On_Wait_Cnt_H, #0 ; Reset counter for infinite delay
  6732. beep_delay_set:
  6733. clr C
  6734. mov A, Power_On_Wait_Cnt_H
  6735. subb A, Temp1 ; Check against chosen delay
  6736. jc wait_for_power_on_no_beep; Has delay elapsed?
  6737. call switch_power_off ; Switch power off in case braking is set
  6738. call wait1ms
  6739. dec Power_On_Wait_Cnt_H ; Decrement high wait counter
  6740. mov Power_On_Wait_Cnt_L, #0 ; Set low wait counter
  6741. mov Temp1, #Pgm_Beacon_Strength
  6742. mov Beep_Strength, @Temp1
  6743. clr EA ; Disable all interrupts
  6744. call beep_f4 ; Signal that there is no signal
  6745. setb EA ; Enable all interrupts
  6746. mov Temp1, #Pgm_Beep_Strength
  6747. mov Beep_Strength, @Temp1
  6748. call wait100ms ; Wait for new RC pulse to be measured
  6749. wait_for_power_on_no_beep:
  6750. call wait10ms
  6751. mov A, Rcp_Timeout_Cntd ; Load RC pulse timeout counter value
  6752. jnz wait_for_power_on_ppm_not_missing ; If it is not zero - proceed
  6753. jnb Flags2.RCP_PPM, wait_for_power_on_ppm_not_missing ; If flag is not set (PWM) - branch
  6754. jmp init_no_signal ; If ppm and pulses missing - go back to detect input signal
  6755. wait_for_power_on_ppm_not_missing:
  6756. mov Temp1, #RCP_STOP
  6757. jb Flags2.RCP_PPM, ($+5) ; If flag is set (PPM) - branch
  6758. mov Temp1, #(RCP_STOP+5) ; Higher than stop (for pwm)
  6759. clr C
  6760. mov A, New_Rcp ; Load new RC pulse value
  6761. subb A, Temp1 ; Higher than stop (plus some hysteresis)?
  6762. jc wait_for_power_on_loop ; No - start over
  6763. IF MODE >= 1 ; Tail or multi
  6764. mov Temp1, #Pgm_Direction ; Check if bidirectional operation
  6765. mov A, @Temp1
  6766. clr C
  6767. subb A, #3
  6768. jz wait_for_power_on_check_timeout ; Do not wait if bidirectional operation
  6769. ENDIF
  6770. lcall wait100ms ; Wait to see if start pulse was only a glitch
  6771. wait_for_power_on_check_timeout:
  6772. mov A, Rcp_Timeout_Cntd ; Load RC pulse timeout counter value
  6773. jnz ($+5) ; If it is not zero - proceed
  6774. ljmp init_no_signal ; If it is zero (pulses missing) - go back to detect input signal
  6775. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  6776. ;
  6777. ; Start entry point
  6778. ;
  6779. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  6780. init_start:
  6781. clr EA
  6782. call switch_power_off
  6783. clr A
  6784. mov Requested_Pwm, A ; Set requested pwm to zero
  6785. mov Governor_Req_Pwm, A ; Set governor requested pwm to zero
  6786. mov Current_Pwm, A ; Set current pwm to zero
  6787. mov Current_Pwm_Limited, A ; Set limited current pwm to zero
  6788. mov Current_Pwm_Lim_Dith, A
  6789. mov Pwm_Dither_Excess_Power, A
  6790. setb EA
  6791. mov Temp1, #Pgm_Motor_Idle ; Set idle pwm to programmed value
  6792. mov A, @Temp1
  6793. clr C
  6794. rlc A
  6795. mov Pwm_Motor_Idle, A
  6796. clr A
  6797. mov Gov_Target_L, A ; Set target to zero
  6798. mov Gov_Target_H, A
  6799. mov Gov_Integral_L, A ; Set integral to zero
  6800. mov Gov_Integral_H, A
  6801. mov Gov_Integral_X, A
  6802. mov Adc_Conversion_Cnt, A
  6803. mov Flags0, A ; Clear flags0
  6804. mov Flags1, A ; Clear flags1
  6805. mov Demag_Detected_Metric, A ; Clear demag metric
  6806. ;**** **** **** **** ****
  6807. ; Motor start beginning
  6808. ;**** **** **** **** ****
  6809. mov Adc_Conversion_Cnt, #TEMP_CHECK_RATE ; Make sure a temp reading is done
  6810. Set_Adc_Ip_Temp
  6811. call wait1ms
  6812. call start_adc_conversion
  6813. read_initial_temp:
  6814. jnb AD0INT, read_initial_temp
  6815. Read_Adc_Result ; Read initial temperature
  6816. mov A, Temp2
  6817. jnz ($+3) ; Is reading below 256?
  6818. mov Temp1, A ; Yes - set average temperature value to zero
  6819. mov Current_Average_Temp, Temp1 ; Set initial average temperature
  6820. call check_temp_voltage_and_limit_power
  6821. mov Adc_Conversion_Cnt, #TEMP_CHECK_RATE ; Make sure a temp reading is done next time
  6822. Set_Adc_Ip_Temp
  6823. ; Set up start operating conditions
  6824. call decode_parameters ; (Decode_parameters uses Temp1 and Temp8)
  6825. ; Set max allowed power
  6826. clr EA ; Disable interrupts to avoid that Requested_Pwm is overwritten
  6827. mov Pwm_Limit, #0FFh ; Set pwm limit to max
  6828. call set_startup_pwm
  6829. mov Pwm_Limit, Requested_Pwm
  6830. mov Pwm_Limit_Spoolup, Requested_Pwm
  6831. mov Pwm_Limit_By_Rpm, Requested_Pwm
  6832. setb EA
  6833. mov Requested_Pwm, #1 ; Set low pwm again after calling set_startup_pwm
  6834. mov Current_Pwm, #1
  6835. mov Current_Pwm_Limited, #1
  6836. mov Current_Pwm_Lim_Dith, #1
  6837. mov Spoolup_Limit_Cnt, Auto_Bailout_Armed
  6838. mov Spoolup_Limit_Skip, #1
  6839. ; Begin startup sequence
  6840. IF MCU_48MHZ == 1
  6841. Set_MCU_Clk_48MHz
  6842. ENDIF
  6843. mov Temp1, #Pgm_Direction ; Check if bidirectional operation
  6844. mov A, @Temp1
  6845. cjne A, #3, init_start_bidir_done
  6846. clr Flags3.PGM_DIR_REV ; Set spinning direction. Default fwd
  6847. jnb Flags2.RCP_DIR_REV, ($+5) ; Check force direction
  6848. setb Flags3.PGM_DIR_REV ; Set spinning direction
  6849. init_start_bidir_done:
  6850. setb Flags1.MOTOR_SPINNING ; Set motor spinning flag
  6851. setb Flags1.STARTUP_PHASE ; Set startup phase flag
  6852. mov Startup_Cnt, #0 ; Reset counter
  6853. call comm5comm6 ; Initialize commutation
  6854. call comm6comm1
  6855. call initialize_timing ; Initialize timing
  6856. call calc_next_comm_timing ; Set virtual commutation point
  6857. call initialize_timing ; Initialize timing
  6858. call calc_next_comm_timing
  6859. call initialize_timing ; Initialize timing
  6860. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  6861. ;
  6862. ; Run entry point
  6863. ;
  6864. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  6865. ; Run 1 = B(p-on) + C(n-pwm) - comparator A evaluated
  6866. ; Out_cA changes from low to high
  6867. run1:
  6868. call wait_for_comp_out_high ; Wait zero cross wait and wait for high
  6869. ; setup_comm_wait ; Setup wait time from zero cross to commutation
  6870. ; evaluate_comparator_integrity ; Check whether comparator reading has been normal
  6871. call calc_governor_target ; Calculate governor target
  6872. call wait_for_comm ; Wait from zero cross to commutation
  6873. call comm1comm2 ; Commutate
  6874. call calc_next_comm_timing ; Calculate next timing and start advance timing wait
  6875. ; wait_advance_timing ; Wait advance timing and start zero cross wait
  6876. ; calc_new_wait_times
  6877. ; wait_before_zc_scan ; Wait zero cross wait and start zero cross timeout
  6878. ; Run 2 = A(p-on) + C(n-pwm) - comparator B evaluated
  6879. ; Out_cB changes from high to low
  6880. run2:
  6881. call wait_for_comp_out_low
  6882. ; setup_comm_wait
  6883. ; evaluate_comparator_integrity
  6884. jnb Flags1.GOV_ACTIVE, ($+6)
  6885. lcall calc_governor_prop_error
  6886. jb Flags0.HIGH_RPM, ($+6) ; Skip if high rpm
  6887. lcall set_pwm_limit_low_rpm
  6888. jnb Flags0.HIGH_RPM, ($+6) ; Do if high rpm
  6889. lcall set_pwm_limit_high_rpm
  6890. call wait_for_comm
  6891. call comm2comm3
  6892. call calc_next_comm_timing
  6893. ; wait_advance_timing
  6894. ; calc_new_wait_times
  6895. ; wait_before_zc_scan
  6896. ; Run 3 = A(p-on) + B(n-pwm) - comparator C evaluated
  6897. ; Out_cC changes from low to high
  6898. run3:
  6899. call wait_for_comp_out_high
  6900. ; setup_comm_wait
  6901. ; evaluate_comparator_integrity
  6902. jnb Flags1.GOV_ACTIVE, ($+6)
  6903. lcall calc_governor_int_error
  6904. call wait_for_comm
  6905. call comm3comm4
  6906. call calc_next_comm_timing
  6907. ; wait_advance_timing
  6908. ; calc_new_wait_times
  6909. ; wait_before_zc_scan
  6910. ; Run 4 = C(p-on) + B(n-pwm) - comparator A evaluated
  6911. ; Out_cA changes from high to low
  6912. run4:
  6913. call wait_for_comp_out_low
  6914. ; setup_comm_wait
  6915. ; evaluate_comparator_integrity
  6916. jnb Flags1.GOV_ACTIVE, ($+6)
  6917. lcall calc_governor_prop_correction
  6918. call wait_for_comm
  6919. call comm4comm5
  6920. call calc_next_comm_timing
  6921. ; wait_advance_timing
  6922. ; calc_new_wait_times
  6923. ; wait_before_zc_scan
  6924. ; Run 5 = C(p-on) + A(n-pwm) - comparator B evaluated
  6925. ; Out_cB changes from low to high
  6926. run5:
  6927. call wait_for_comp_out_high
  6928. ; setup_comm_wait
  6929. ; evaluate_comparator_integrity
  6930. jnb Flags1.GOV_ACTIVE, ($+6)
  6931. lcall calc_governor_int_correction
  6932. call wait_for_comm
  6933. call comm5comm6
  6934. call calc_next_comm_timing
  6935. ; wait_advance_timing
  6936. ; calc_new_wait_times
  6937. ; wait_before_zc_scan
  6938. ; Run 6 = B(p-on) + A(n-pwm) - comparator C evaluated
  6939. ; Out_cC changes from high to low
  6940. run6:
  6941. call start_adc_conversion
  6942. call wait_for_comp_out_low
  6943. ; setup_comm_wait
  6944. ; evaluate_comparator_integrity
  6945. call wait_for_comm
  6946. call comm6comm1
  6947. call check_temp_voltage_and_limit_power
  6948. call calc_next_comm_timing
  6949. ; wait_advance_timing
  6950. ; calc_new_wait_times
  6951. ; wait_before_zc_scan
  6952. ; Check if it is direct startup
  6953. jnb Flags1.STARTUP_PHASE, normal_run_checks
  6954. ; Set spoolup power variables
  6955. mov Pwm_Limit, Pwm_Spoolup_Beg ; Set initial max power
  6956. mov Pwm_Limit_Spoolup, Pwm_Spoolup_Beg ; Set initial slow spoolup power
  6957. mov Spoolup_Limit_Cnt, Auto_Bailout_Armed
  6958. mov Spoolup_Limit_Skip, #1
  6959. ; Check startup counter
  6960. mov Temp2, #24 ; Set nominal startup parameters
  6961. mov Temp3, #12
  6962. clr C
  6963. mov A, Startup_Cnt ; Load counter
  6964. subb A, Temp2 ; Is counter above requirement?
  6965. jc direct_start_check_rcp ; No - proceed
  6966. clr Flags1.STARTUP_PHASE ; Clear startup phase flag
  6967. setb Flags1.INITIAL_RUN_PHASE ; Set initial run phase flag
  6968. mov Initial_Run_Rot_Cntd, Temp3 ; Set initial run rotation count
  6969. IF MODE == 1 ; Tail
  6970. mov Pwm_Limit, #0FFh ; Allow full power
  6971. ENDIF
  6972. IF MODE == 2 ; Multi
  6973. mov Pwm_Limit, Pwm_Spoolup_Beg
  6974. mov Pwm_Limit_By_Rpm, Pwm_Spoolup_Beg
  6975. ENDIF
  6976. jmp normal_run_checks
  6977. direct_start_check_rcp:
  6978. clr C
  6979. mov A, New_Rcp ; Load new pulse value
  6980. subb A, #RCP_STOP ; Check if pulse is below stop value
  6981. jc ($+5)
  6982. ljmp run1 ; Continue to run
  6983. jmp run_to_wait_for_power_on
  6984. normal_run_checks:
  6985. ; Check if it is initial run phase
  6986. jnb Flags1.INITIAL_RUN_PHASE, initial_run_phase_done ; If not initial run phase - branch
  6987. jb Flags1.DIR_CHANGE_BRAKE, initial_run_phase_done ; If a direction change - branch
  6988. ; Decrement startup rotaton count
  6989. mov A, Initial_Run_Rot_Cntd
  6990. dec A
  6991. ; Check number of initial rotations
  6992. jnz normal_run_check_startup_rot ; Branch if counter is not zero
  6993. clr Flags1.INITIAL_RUN_PHASE ; Clear initial run phase flag
  6994. setb Flags1.MOTOR_STARTED ; Set motor started
  6995. jmp run1 ; Continue with normal run
  6996. normal_run_check_startup_rot:
  6997. mov Initial_Run_Rot_Cntd, A ; Not zero - store counter
  6998. clr C
  6999. mov A, New_Rcp ; Load new pulse value
  7000. subb A, #RCP_STOP ; Check if pulse is below stop value
  7001. jc ($+5)
  7002. ljmp run1 ; Continue to run
  7003. mov Temp1, #Pgm_Direction ; Check if bidirectional operation
  7004. mov A, @Temp1
  7005. clr C
  7006. subb A, #3
  7007. jz initial_run_phase_done
  7008. jmp run_to_wait_for_power_on
  7009. initial_run_phase_done:
  7010. ; Reset stall count
  7011. mov Stall_Cnt, #0
  7012. IF MODE == 0 ; Main
  7013. ; Check if throttle is zeroed
  7014. clr C
  7015. mov A, Rcp_Stop_Cnt ; Load stop RC pulse counter value
  7016. subb A, #1 ; Is number of stop RC pulses above limit?
  7017. jc run6_check_rcp_stop_count ; If no - branch
  7018. mov Pwm_Limit_Spoolup, Pwm_Spoolup_Beg ; If yes - set initial max powers
  7019. mov Spoolup_Limit_Cnt, Auto_Bailout_Armed ; And set spoolup parameters
  7020. mov Spoolup_Limit_Skip, #1
  7021. run6_check_rcp_stop_count:
  7022. ENDIF
  7023. ; Exit run loop after a given time
  7024. mov Temp1, #RCP_STOP_LIMIT
  7025. mov Temp2, #Pgm_Brake_On_Stop
  7026. mov A, @Temp2
  7027. jz ($+4)
  7028. mov Temp1, #3 ; About 100ms before stopping when brake is set
  7029. clr C
  7030. mov A, Rcp_Stop_Cnt ; Load stop RC pulse counter low byte value
  7031. subb A, Temp1 ; Is number of stop RC pulses above limit?
  7032. jnc run_to_wait_for_power_on ; Yes, go back to wait for poweron
  7033. jnb Flags2.RCP_PPM, run6_check_dir; If flag is not set (PWM) - branch
  7034. mov A, Rcp_Timeout_Cntd ; Load RC pulse timeout counter value
  7035. jz run_to_wait_for_power_on ; If it is zero - go back to wait for poweron
  7036. run6_check_dir:
  7037. IF MODE >= 1 ; Tail or multi
  7038. mov Temp1, #Pgm_Direction ; Check if bidirectional operation
  7039. mov A, @Temp1
  7040. cjne A, #3, run6_check_speed
  7041. jb Flags3.PGM_DIR_REV, run6_check_dir_rev ; Check if actual rotation direction
  7042. jb Flags2.RCP_DIR_REV, run6_check_dir_change ; Matches force direction
  7043. ajmp run6_check_speed
  7044. run6_check_dir_rev:
  7045. jnb Flags2.RCP_DIR_REV, run6_check_dir_change
  7046. ajmp run6_check_speed
  7047. run6_check_dir_change:
  7048. jb Flags1.DIR_CHANGE_BRAKE, run6_check_speed
  7049. setb Flags1.DIR_CHANGE_BRAKE ; Set brake flag
  7050. mov Pwm_Limit, Pwm_Spoolup_Beg ; Set max power while braking
  7051. jmp run4 ; Go back to run 4, thereby changing force direction
  7052. run6_check_speed:
  7053. ENDIF
  7054. mov Temp1, #0F0h ; Default minimum speed
  7055. jnb Flags1.DIR_CHANGE_BRAKE, run6_brake_done; Is it a direction change?
  7056. mov Pwm_Limit, Pwm_Spoolup_Beg ; Set max power while braking
  7057. mov Temp1, #20h ; Bidirectional braking termination speed
  7058. run6_brake_done:
  7059. clr C
  7060. mov A, Comm_Period4x_H ; Is Comm_Period4x more than 32ms (~1220 eRPM)?
  7061. subb A, Temp1
  7062. jnc ($+4) ; Yes - stop or turn direction
  7063. ajmp run1 ; No - go back to run 1
  7064. IF MODE >= 1 ; Tail or multi
  7065. jnb Flags1.DIR_CHANGE_BRAKE, run_to_wait_for_power_on ; If it is not a direction change - stop
  7066. clr Flags1.DIR_CHANGE_BRAKE ; Clear brake flag
  7067. clr Flags3.PGM_DIR_REV ; Set spinning direction. Default fwd
  7068. jnb Flags2.RCP_DIR_REV, ($+5) ; Check force direction
  7069. setb Flags3.PGM_DIR_REV ; Set spinning direction
  7070. setb Flags1.INITIAL_RUN_PHASE
  7071. mov Initial_Run_Rot_Cntd, #18
  7072. mov Pwm_Limit, Pwm_Spoolup_Beg ; Set initial max power
  7073. ajmp run1 ; Go back to run 1
  7074. ENDIF
  7075. run_to_wait_for_power_on_fail:
  7076. inc Stall_Cnt ; Increment stall count
  7077. mov A, New_Rcp ; Check if RCP is zero, then it is a normal stop
  7078. jz run_to_wait_for_power_on
  7079. ajmp run_to_wait_for_power_on_stall_done
  7080. run_to_wait_for_power_on:
  7081. mov Stall_Cnt, #0
  7082. run_to_wait_for_power_on_stall_done:
  7083. clr EA
  7084. call switch_power_off
  7085. mov Temp1, #Pgm_Pwm_Freq
  7086. mov A, @Temp1
  7087. mov Temp7, A ; Store setting in Temp7
  7088. mov @Temp1, #2 ; Set low pwm mode (in order to turn off damping)
  7089. call decode_parameters ; (Decode_parameters uses Temp1 and Temp8)
  7090. mov Temp1, #Pgm_Pwm_Freq
  7091. mov A, Temp7
  7092. mov @Temp1, A ; Restore settings
  7093. clr A
  7094. mov Requested_Pwm, A ; Set requested pwm to zero
  7095. mov Governor_Req_Pwm, A ; Set governor requested pwm to zero
  7096. mov Current_Pwm, A ; Set current pwm to zero
  7097. mov Current_Pwm_Limited, A ; Set limited current pwm to zero
  7098. mov Current_Pwm_Lim_Dith, A
  7099. mov Pwm_Motor_Idle, A ; Set motor idle to zero
  7100. mov Flags0, #0 ; Clear flags0
  7101. mov Flags1, #0 ; Clear flags1
  7102. IF MCU_48MHZ == 1
  7103. Set_MCU_Clk_24MHz
  7104. ENDIF
  7105. setb EA
  7106. call wait100ms ; Wait for pwm to be stopped
  7107. call switch_power_off
  7108. mov Temp1, #Pgm_Brake_On_Stop
  7109. mov A, @Temp1
  7110. jz run_to_wait_for_power_on_brake_done
  7111. Brake_FETs_on
  7112. run_to_wait_for_power_on_brake_done:
  7113. IF MODE == 0 ; Main
  7114. jnb Flags2.RCP_PPM, run_to_next_state_main ; If flag is not set (PWM) - branch
  7115. mov A, Rcp_Timeout_Cntd ; Load RC pulse timeout counter value
  7116. jnz run_to_next_state_main ; If it is not zero - branch
  7117. jmp init_no_signal ; If it is zero (pulses missing) - go back to detect input signal
  7118. run_to_next_state_main:
  7119. mov Temp1, #Pgm_Main_Rearm_Start
  7120. mov A, @Temp1
  7121. clr C
  7122. subb A, #1 ; Is re-armed start enabled?
  7123. jc jmp_wait_for_power_on ; No - do like tail and start immediately
  7124. jmp validate_rcp_start ; Yes - go back to validate RC pulse
  7125. jmp_wait_for_power_on:
  7126. jmp wait_for_power_on ; Go back to wait for power on
  7127. ENDIF
  7128. IF MODE >= 1 ; Tail or multi
  7129. jnb Flags2.RCP_PPM, jmp_wait_for_power_on ; If flag is not set (PWM) - branch
  7130. clr C
  7131. mov A, Stall_Cnt
  7132. subb A, #4
  7133. jc jmp_wait_for_power_on
  7134. jmp init_no_signal
  7135. jmp_wait_for_power_on:
  7136. jmp wait_for_power_on ; Go back to wait for power on
  7137. ENDIF
  7138. $include (BLHeliTxPgm.inc) ; Include source code for programming the ESC with the TX
  7139. $include (BLHeliBootLoad.inc) ; Include source code for bootloader
  7140. ;**** **** **** **** **** **** **** **** **** **** **** **** ****
  7141. CSEG AT 19FDh
  7142. reset:
  7143. ljmp pgm_start
  7144. END