RCOutput.cpp 47 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495969798991001011021031041051061071081091101111121131141151161171181191201211221231241251261271281291301311321331341351361371381391401411421431441451461471481491501511521531541551561571581591601611621631641651661671681691701711721731741751761771781791801811821831841851861871881891901911921931941951961971981992002012022032042052062072082092102112122132142152162172182192202212222232242252262272282292302312322332342352362372382392402412422432442452462472482492502512522532542552562572582592602612622632642652662672682692702712722732742752762772782792802812822832842852862872882892902912922932942952962972982993003013023033043053063073083093103113123133143153163173183193203213223233243253263273283293303313323333343353363373383393403413423433443453463473483493503513523533543553563573583593603613623633643653663673683693703713723733743753763773783793803813823833843853863873883893903913923933943953963973983994004014024034044054064074084094104114124134144154164174184194204214224234244254264274284294304314324334344354364374384394404414424434444454464474484494504514524534544554564574584594604614624634644654664674684694704714724734744754764774784794804814824834844854864874884894904914924934944954964974984995005015025035045055065075085095105115125135145155165175185195205215225235245255265275285295305315325335345355365375385395405415425435445455465475485495505515525535545555565575585595605615625635645655665675685695705715725735745755765775785795805815825835845855865875885895905915925935945955965975985996006016026036046056066076086096106116126136146156166176186196206216226236246256266276286296306316326336346356366376386396406416426436446456466476486496506516526536546556566576586596606616626636646656666676686696706716726736746756766776786796806816826836846856866876886896906916926936946956966976986997007017027037047057067077087097107117127137147157167177187197207217227237247257267277287297307317327337347357367377387397407417427437447457467477487497507517527537547557567577587597607617627637647657667677687697707717727737747757767777787797807817827837847857867877887897907917927937947957967977987998008018028038048058068078088098108118128138148158168178188198208218228238248258268278288298308318328338348358368378388398408418428438448458468478488498508518528538548558568578588598608618628638648658668678688698708718728738748758768778788798808818828838848858868878888898908918928938948958968978988999009019029039049059069079089099109119129139149159169179189199209219229239249259269279289299309319329339349359369379389399409419429439449459469479489499509519529539549559569579589599609619629639649659669679689699709719729739749759769779789799809819829839849859869879889899909919929939949959969979989991000100110021003100410051006100710081009101010111012101310141015101610171018101910201021102210231024102510261027102810291030103110321033103410351036103710381039104010411042104310441045104610471048104910501051105210531054105510561057105810591060106110621063106410651066106710681069107010711072107310741075107610771078107910801081108210831084108510861087108810891090109110921093109410951096109710981099110011011102110311041105110611071108110911101111111211131114111511161117111811191120112111221123112411251126112711281129113011311132113311341135113611371138113911401141114211431144114511461147114811491150115111521153115411551156115711581159116011611162116311641165116611671168116911701171117211731174117511761177117811791180118111821183118411851186118711881189119011911192119311941195119611971198119912001201120212031204120512061207120812091210121112121213121412151216121712181219122012211222122312241225122612271228122912301231123212331234123512361237123812391240124112421243124412451246124712481249125012511252125312541255125612571258125912601261126212631264126512661267126812691270127112721273127412751276127712781279128012811282128312841285128612871288128912901291129212931294129512961297129812991300130113021303130413051306130713081309131013111312131313141315131613171318131913201321132213231324132513261327132813291330133113321333133413351336133713381339134013411342134313441345134613471348134913501351135213531354135513561357135813591360136113621363136413651366136713681369137013711372137313741375137613771378137913801381138213831384138513861387138813891390139113921393139413951396139713981399140014011402140314041405140614071408140914101411141214131414141514161417141814191420142114221423142414251426142714281429143014311432143314341435143614371438143914401441144214431444144514461447144814491450145114521453145414551456145714581459146014611462146314641465146614671468146914701471147214731474147514761477147814791480148114821483148414851486148714881489149014911492149314941495149614971498149915001501150215031504150515061507150815091510151115121513151415151516151715181519152015211522152315241525152615271528152915301531153215331534153515361537153815391540154115421543154415451546154715481549155015511552155315541555155615571558155915601561156215631564156515661567156815691570157115721573157415751576157715781579158015811582158315841585158615871588158915901591159215931594159515961597159815991600160116021603160416051606160716081609161016111612161316141615161616171618161916201621162216231624162516261627162816291630163116321633163416351636163716381639164016411642164316441645164616471648164916501651165216531654
  1. /*
  2. * This file is free software: you can redistribute it and/or modify it
  3. * under the terms of the GNU General Public License as published by the
  4. * Free Software Foundation, either version 3 of the License, or
  5. * (at your option) any later version.
  6. *
  7. * This file is distributed in the hope that it will be useful, but
  8. * WITHOUT ANY WARRANTY; without even the implied warranty of
  9. * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
  10. * See the GNU General Public License for more details.
  11. *
  12. * You should have received a copy of the GNU General Public License along
  13. * with this program. If not, see <http://www.gnu.org/licenses/>.
  14. *
  15. * Code by Andrew Tridgell and Siddharth Bharat Purohit
  16. */
  17. #include "RCOutput.h"
  18. #include <AP_Math/AP_Math.h>
  19. #include <AP_BoardConfig/AP_BoardConfig.h>
  20. #include <AP_HAL/utility/RingBuffer.h>
  21. #include "GPIO.h"
  22. #include "hwdef/common/stm32_util.h"
  23. #include "hwdef/common/watchdog.h"
  24. #if HAL_USE_PWM == TRUE
  25. using namespace ChibiOS;
  26. extern const AP_HAL::HAL& hal;
  27. #if HAL_WITH_IO_MCU
  28. #include <AP_IOMCU/AP_IOMCU.h>
  29. extern AP_IOMCU iomcu;
  30. #endif
  31. #define RCOU_SERIAL_TIMING_DEBUG 0
  32. struct RCOutput::pwm_group RCOutput::pwm_group_list[] = { HAL_PWM_GROUPS };
  33. struct RCOutput::irq_state RCOutput::irq;
  34. #define NUM_GROUPS ARRAY_SIZE(pwm_group_list)
  35. // marker for a disabled channel
  36. #define CHAN_DISABLED 255
  37. // #pragma GCC optimize("Og")
  38. /*
  39. initialise RC output driver
  40. */
  41. void RCOutput::init()
  42. {
  43. uint8_t pwm_count = AP_BoardConfig::get_pwm_count();
  44. for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
  45. //Start Pwm groups
  46. pwm_group &group = pwm_group_list[i];
  47. group.current_mode = MODE_PWM_NORMAL;
  48. for (uint8_t j = 0; j < 4; j++ ) {
  49. uint8_t chan = group.chan[j];
  50. if (chan >= pwm_count) {
  51. group.chan[j] = CHAN_DISABLED;
  52. }
  53. if (group.chan[j] != CHAN_DISABLED) {
  54. num_fmu_channels = MAX(num_fmu_channels, group.chan[j]+1);
  55. group.ch_mask |= (1U<<group.chan[j]);
  56. }
  57. }
  58. if (group.ch_mask != 0) {
  59. pwmStart(group.pwm_drv, &group.pwm_cfg);
  60. group.pwm_started = true;
  61. }
  62. chVTObjectInit(&group.dma_timeout);
  63. }
  64. #if HAL_WITH_IO_MCU
  65. if (AP_BoardConfig::io_enabled()) {
  66. iomcu.init();
  67. // with IOMCU the local (FMU) channels start at 8
  68. chan_offset = 8;
  69. }
  70. #endif
  71. chMtxObjectInit(&trigger_mutex);
  72. // setup default output rate of 50Hz
  73. set_freq(0xFFFF ^ ((1U<<chan_offset)-1), 50);
  74. #ifdef HAL_GPIO_PIN_SAFETY_IN
  75. safety_state = AP_HAL::Util::SAFETY_DISARMED;
  76. #endif
  77. }
  78. /*
  79. setup the output frequency for a group and start pwm output
  80. */
  81. void RCOutput::set_freq_group(pwm_group &group)
  82. {
  83. if (mode_requires_dma(group.current_mode)) {
  84. // speed setup in DMA handler
  85. return;
  86. }
  87. uint16_t freq_set = group.rc_frequency;
  88. uint32_t old_clock = group.pwm_cfg.frequency;
  89. uint32_t old_period = group.pwm_cfg.period;
  90. if (freq_set > 400 || group.current_mode == MODE_PWM_ONESHOT125) {
  91. // use a 8MHz clock for higher frequencies or for
  92. // oneshot125. Using 8MHz for oneshot125 results in the full
  93. // 1000 steps for smooth output
  94. group.pwm_cfg.frequency = 8000000;
  95. } else if (freq_set <= 400) {
  96. // use a 1MHz clock
  97. group.pwm_cfg.frequency = 1000000;
  98. }
  99. // check if the frequency is possible, and keep halving
  100. // down to 1MHz until it is OK with the hardware timer we
  101. // are using. If we don't do this we'll hit an assert in
  102. // the ChibiOS PWM driver on some timers
  103. PWMDriver *pwmp = group.pwm_drv;
  104. uint32_t psc = (pwmp->clock / pwmp->config->frequency) - 1;
  105. while ((psc > 0xFFFF || ((psc + 1) * pwmp->config->frequency) != pwmp->clock) &&
  106. group.pwm_cfg.frequency > 1000000) {
  107. group.pwm_cfg.frequency /= 2;
  108. psc = (pwmp->clock / pwmp->config->frequency) - 1;
  109. }
  110. if (group.current_mode == MODE_PWM_ONESHOT ||
  111. group.current_mode == MODE_PWM_ONESHOT125) {
  112. // force a period of 0, meaning no pulses till we trigger
  113. group.pwm_cfg.period = 0;
  114. } else {
  115. group.pwm_cfg.period = group.pwm_cfg.frequency/freq_set;
  116. }
  117. bool force_reconfig = false;
  118. for (uint8_t j=0; j<4; j++) {
  119. if (group.pwm_cfg.channels[j].mode == PWM_OUTPUT_ACTIVE_LOW) {
  120. group.pwm_cfg.channels[j].mode = PWM_OUTPUT_ACTIVE_HIGH;
  121. force_reconfig = true;
  122. }
  123. if (group.pwm_cfg.channels[j].mode == PWM_COMPLEMENTARY_OUTPUT_ACTIVE_LOW) {
  124. group.pwm_cfg.channels[j].mode = PWM_COMPLEMENTARY_OUTPUT_ACTIVE_HIGH;
  125. force_reconfig = true;
  126. }
  127. }
  128. if (old_clock != group.pwm_cfg.frequency ||
  129. old_period != group.pwm_cfg.period ||
  130. !group.pwm_started ||
  131. force_reconfig) {
  132. // we need to stop and start to setup the new clock
  133. if (group.pwm_started) {
  134. pwmStop(group.pwm_drv);
  135. }
  136. pwmStart(group.pwm_drv, &group.pwm_cfg);
  137. group.pwm_started = true;
  138. }
  139. pwmChangePeriod(group.pwm_drv, group.pwm_cfg.period);
  140. }
  141. /*
  142. set output frequency in HZ for a set of channels given by a mask
  143. */
  144. void RCOutput::set_freq(uint32_t chmask, uint16_t freq_hz)
  145. {
  146. #if HAL_WITH_IO_MCU
  147. if (AP_BoardConfig::io_enabled()) {
  148. // change frequency on IOMCU
  149. uint16_t io_chmask = chmask & 0xFF;
  150. if (io_chmask) {
  151. // disallow changing frequency of this group if it is greater than the default
  152. for (uint8_t i=0; i<ARRAY_SIZE(iomcu.ch_masks); i++) {
  153. const uint16_t mask = io_chmask & iomcu.ch_masks[i];
  154. if (mask != 0) {
  155. if (freq_hz > 50) {
  156. io_fast_channel_mask |= mask;
  157. } else {
  158. io_fast_channel_mask &= ~mask;
  159. }
  160. }
  161. }
  162. iomcu.set_freq(io_fast_channel_mask, freq_hz);
  163. }
  164. }
  165. #endif
  166. // convert to a local (FMU) channel mask
  167. chmask >>= chan_offset;
  168. if (chmask == 0) {
  169. return;
  170. }
  171. /*
  172. we enable the new frequency on all groups that have one
  173. of the requested channels. This means we may enable high
  174. speed on some channels that aren't requested, but that
  175. is needed in order to fly a vehicle such as a hex
  176. multicopter properly
  177. */
  178. for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
  179. // greater than 400 doesn't give enough room at higher periods for
  180. // the down pulse. This still allows for high rate with oneshot and dshot.
  181. pwm_group &group = pwm_group_list[i];
  182. uint16_t group_freq = freq_hz;
  183. if (group_freq > 400 && group.current_mode != MODE_PWM_BRUSHED) {
  184. group_freq = 400;
  185. }
  186. if ((group.ch_mask & chmask) != 0) {
  187. group.rc_frequency = group_freq;
  188. set_freq_group(group);
  189. // disallow changing frequency of this group if it is greater than the default
  190. if (group_freq > 50) {
  191. fast_channel_mask |= group.ch_mask;
  192. }
  193. }
  194. }
  195. }
  196. /*
  197. set default output rate
  198. */
  199. void RCOutput::set_default_rate(uint16_t freq_hz)
  200. {
  201. #if HAL_WITH_IO_MCU
  202. if (AP_BoardConfig::io_enabled()) {
  203. iomcu.set_default_rate(freq_hz);
  204. }
  205. #endif
  206. for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
  207. pwm_group &group = pwm_group_list[i];
  208. if ((group.ch_mask & fast_channel_mask) || group.ch_mask == 0) {
  209. // don't change fast channels
  210. continue;
  211. }
  212. group.pwm_cfg.period = group.pwm_cfg.frequency/freq_hz;
  213. if (group.pwm_started) {
  214. pwmChangePeriod(group.pwm_drv, group.pwm_cfg.period);
  215. }
  216. }
  217. }
  218. /*
  219. find pwm_group and index in group given a channel number
  220. */
  221. RCOutput::pwm_group *RCOutput::find_chan(uint8_t chan, uint8_t &group_idx)
  222. {
  223. if (chan >= max_channels) {
  224. return nullptr;
  225. }
  226. if (chan < chan_offset) {
  227. return nullptr;
  228. }
  229. chan -= chan_offset;
  230. for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
  231. pwm_group &group = pwm_group_list[i];
  232. for (uint8_t j = 0; j < 4; j++) {
  233. if (group.chan[j] == chan) {
  234. group_idx = j;
  235. return &group;
  236. }
  237. }
  238. }
  239. return nullptr;
  240. }
  241. uint16_t RCOutput::get_freq(uint8_t chan)
  242. {
  243. #if HAL_WITH_IO_MCU
  244. if (chan < chan_offset) {
  245. return iomcu.get_freq(chan);
  246. }
  247. #endif
  248. uint8_t i;
  249. pwm_group *grp = find_chan(chan, i);
  250. if (grp) {
  251. return grp->pwm_drv->config->frequency / grp->pwm_drv->period;
  252. }
  253. // assume 50Hz default
  254. return 50;
  255. }
  256. void RCOutput::enable_ch(uint8_t chan)
  257. {
  258. uint8_t i;
  259. pwm_group *grp = find_chan(chan, i);
  260. if (grp) {
  261. en_mask |= 1U << (chan - chan_offset);
  262. }
  263. }
  264. void RCOutput::disable_ch(uint8_t chan)
  265. {
  266. uint8_t i;
  267. pwm_group *grp = find_chan(chan, i);
  268. if (grp) {
  269. pwmDisableChannel(grp->pwm_drv, i);
  270. en_mask &= ~(1U<<(chan - chan_offset));
  271. }
  272. }
  273. void RCOutput::write(uint8_t chan, uint16_t period_us)
  274. {
  275. if (chan >= max_channels) {
  276. return;
  277. }
  278. last_sent[chan] = period_us;
  279. #if HAL_WITH_IO_MCU
  280. // handle IO MCU channels
  281. if (AP_BoardConfig::io_enabled()) {
  282. uint16_t io_period_us = period_us;
  283. if (iomcu_oneshot125 && ((1U<<chan) & io_fast_channel_mask)) {
  284. // the iomcu only has one oneshot setting, so we need to scale by a factor
  285. // of 8 here for oneshot125
  286. io_period_us /= 8;
  287. }
  288. iomcu.write_channel(chan, io_period_us);
  289. }
  290. #endif
  291. if (chan < chan_offset) {
  292. return;
  293. }
  294. if (safety_state == AP_HAL::Util::SAFETY_DISARMED && !(safety_mask & (1U<<chan))) {
  295. // implement safety pwm value
  296. period_us = safe_pwm[chan];
  297. }
  298. chan -= chan_offset;
  299. period[chan] = period_us;
  300. if (chan < num_fmu_channels) {
  301. active_fmu_channels = MAX(chan+1, active_fmu_channels);
  302. if (!corked) {
  303. push_local();
  304. }
  305. }
  306. }
  307. /*
  308. push values to local channels from period[] array
  309. */
  310. void RCOutput::push_local(void)
  311. {
  312. if (active_fmu_channels == 0) {
  313. return;
  314. }
  315. uint16_t outmask = (1U<<active_fmu_channels)-1;
  316. outmask &= en_mask;
  317. uint16_t widest_pulse = 0;
  318. uint8_t need_trigger = 0;
  319. bool safety_on = hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED;
  320. for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
  321. pwm_group &group = pwm_group_list[i];
  322. if (serial_group) {
  323. continue;
  324. }
  325. if (!group.pwm_started) {
  326. continue;
  327. }
  328. for (uint8_t j = 0; j < 4; j++) {
  329. uint8_t chan = group.chan[j];
  330. if (chan == CHAN_DISABLED) {
  331. continue;
  332. }
  333. if (outmask & (1UL<<chan)) {
  334. uint32_t period_us = period[chan];
  335. if (safety_on && !(safety_mask & (1U<<(chan+chan_offset)))) {
  336. // safety is on, overwride pwm
  337. period_us = safe_pwm[chan+chan_offset];
  338. }
  339. if (group.current_mode == MODE_PWM_BRUSHED) {
  340. if (period_us <= _esc_pwm_min) {
  341. period_us = 0;
  342. } else if (period_us >= _esc_pwm_max) {
  343. period_us = PWM_FRACTION_TO_WIDTH(group.pwm_drv, 1, 1);
  344. } else {
  345. period_us = PWM_FRACTION_TO_WIDTH(group.pwm_drv,\
  346. (_esc_pwm_max - _esc_pwm_min), (period_us - _esc_pwm_min));
  347. }
  348. pwmEnableChannel(group.pwm_drv, j, period_us);
  349. } else if (group.current_mode == MODE_PWM_ONESHOT125) {
  350. // this gives us a width in 125 ns increments, giving 1000 steps over the 125 to 250 range
  351. uint32_t width = ((group.pwm_cfg.frequency/1000000U) * period_us) / 8U;
  352. pwmEnableChannel(group.pwm_drv, j, width);
  353. // scale the period down so we don't delay for longer than we need to
  354. period_us /= 8;
  355. }
  356. else if (group.current_mode < MODE_PWM_DSHOT150) {
  357. uint32_t width = (group.pwm_cfg.frequency/1000000U) * period_us;
  358. pwmEnableChannel(group.pwm_drv, j, width);
  359. }
  360. #ifndef DISABLE_DSHOT
  361. else if (is_dshot_protocol(group.current_mode) || group.current_mode == MODE_NEOPIXEL) {
  362. // set period_us to time for pulse output, to enable very fast rates
  363. period_us = dshot_pulse_time_us;
  364. }
  365. #endif //#ifndef DISABLE_DSHOT
  366. if (period_us > widest_pulse) {
  367. widest_pulse = period_us;
  368. }
  369. if (group.current_mode == MODE_PWM_ONESHOT ||
  370. group.current_mode == MODE_PWM_ONESHOT125 ||
  371. group.current_mode == MODE_NEOPIXEL ||
  372. is_dshot_protocol(group.current_mode)) {
  373. need_trigger |= (1U<<i);
  374. }
  375. }
  376. }
  377. }
  378. if (widest_pulse > 2300) {
  379. widest_pulse = 2300;
  380. }
  381. trigger_widest_pulse = widest_pulse;
  382. trigger_groupmask = need_trigger;
  383. if (trigger_groupmask) {
  384. trigger_groups();
  385. }
  386. }
  387. uint16_t RCOutput::read(uint8_t chan)
  388. {
  389. if (chan >= max_channels) {
  390. return 0;
  391. }
  392. #if HAL_WITH_IO_MCU
  393. if (chan < chan_offset) {
  394. return iomcu.read_channel(chan);
  395. }
  396. #endif
  397. chan -= chan_offset;
  398. return period[chan];
  399. }
  400. void RCOutput::read(uint16_t* period_us, uint8_t len)
  401. {
  402. if (len > max_channels) {
  403. len = max_channels;
  404. }
  405. #if HAL_WITH_IO_MCU
  406. for (uint8_t i=0; i<MIN(len, chan_offset); i++) {
  407. period_us[i] = iomcu.read_channel(i);
  408. }
  409. #endif
  410. if (len <= chan_offset) {
  411. return;
  412. }
  413. len -= chan_offset;
  414. period_us += chan_offset;
  415. memcpy(period_us, period, len*sizeof(uint16_t));
  416. }
  417. uint16_t RCOutput::read_last_sent(uint8_t chan)
  418. {
  419. if (chan >= max_channels) {
  420. return 0;
  421. }
  422. return last_sent[chan];
  423. }
  424. void RCOutput::read_last_sent(uint16_t* period_us, uint8_t len)
  425. {
  426. if (len > max_channels) {
  427. len = max_channels;
  428. }
  429. for (uint8_t i=0; i<len; i++) {
  430. period_us[i] = read_last_sent(i);
  431. }
  432. }
  433. /*
  434. does an output mode require the use of the UP DMA channel?
  435. */
  436. bool RCOutput::mode_requires_dma(enum output_mode mode) const
  437. {
  438. #ifdef DISABLE_DSHOT
  439. return false;
  440. #else
  441. return is_dshot_protocol(mode) || (mode == MODE_NEOPIXEL);
  442. #endif //#ifdef DISABLE_DSHOT
  443. }
  444. /*
  445. setup a group for DMA output at a given bitrate. The bit_width is
  446. the value for a pulse width in the DMA buffer for a full bit.
  447. This is used for both DShot and serial output
  448. */
  449. bool RCOutput::setup_group_DMA(pwm_group &group, uint32_t bitrate, uint32_t bit_width, bool active_high, const uint16_t buffer_length)
  450. {
  451. #ifndef DISABLE_DSHOT
  452. if (!group.dma_buffer || buffer_length != group.dma_buffer_len) {
  453. if (group.dma_buffer) {
  454. hal.util->free_type(group.dma_buffer, group.dma_buffer_len, AP_HAL::Util::MEM_DMA_SAFE);
  455. group.dma_buffer_len = 0;
  456. }
  457. group.dma_buffer = (uint32_t *)hal.util->malloc_type(buffer_length, AP_HAL::Util::MEM_DMA_SAFE);
  458. if (!group.dma_buffer) {
  459. return false;
  460. }
  461. group.dma_buffer_len = buffer_length;
  462. }
  463. // for dshot we setup for DMAR based output
  464. if (!group.dma_handle) {
  465. group.dma_handle = new Shared_DMA(group.dma_up_stream_id, SHARED_DMA_NONE,
  466. FUNCTOR_BIND_MEMBER(&RCOutput::dma_allocate, void, Shared_DMA *),
  467. FUNCTOR_BIND_MEMBER(&RCOutput::dma_deallocate, void, Shared_DMA *));
  468. if (!group.dma_handle) {
  469. return false;
  470. }
  471. }
  472. // hold the lock during setup, to ensure there isn't a DMA operation ongoing
  473. group.dma_handle->lock();
  474. // configure timer driver for DMAR at requested rate
  475. if (group.pwm_started) {
  476. pwmStop(group.pwm_drv);
  477. group.pwm_started = false;
  478. }
  479. // adjust frequency to give an allowed value given the
  480. // clock. There is probably a better way to do this
  481. uint32_t clock_hz = group.pwm_drv->clock;
  482. uint32_t target_frequency = bitrate * bit_width;
  483. uint32_t prescaler = clock_hz / target_frequency;
  484. while ((clock_hz / prescaler) * prescaler != clock_hz && prescaler <= 0x8000) {
  485. prescaler++;
  486. }
  487. uint32_t freq = clock_hz / prescaler;
  488. if (prescaler > 0x8000) {
  489. group.dma_handle->unlock();
  490. return false;
  491. }
  492. group.pwm_cfg.frequency = freq;
  493. group.pwm_cfg.period = bit_width;
  494. group.pwm_cfg.dier = TIM_DIER_UDE;
  495. group.pwm_cfg.cr2 = 0;
  496. group.bit_width_mul = (freq + (target_frequency/2)) / target_frequency;
  497. for (uint8_t j=0; j<4; j++) {
  498. pwmmode_t mode = group.pwm_cfg.channels[j].mode;
  499. if (mode != PWM_OUTPUT_DISABLED) {
  500. if(mode == PWM_COMPLEMENTARY_OUTPUT_ACTIVE_LOW || mode == PWM_COMPLEMENTARY_OUTPUT_ACTIVE_HIGH) {
  501. group.pwm_cfg.channels[j].mode = active_high?PWM_COMPLEMENTARY_OUTPUT_ACTIVE_HIGH:PWM_COMPLEMENTARY_OUTPUT_ACTIVE_LOW;
  502. } else {
  503. group.pwm_cfg.channels[j].mode = active_high?PWM_OUTPUT_ACTIVE_HIGH:PWM_OUTPUT_ACTIVE_LOW;
  504. }
  505. }
  506. }
  507. pwmStart(group.pwm_drv, &group.pwm_cfg);
  508. group.pwm_started = true;
  509. for (uint8_t j=0; j<4; j++) {
  510. if (group.chan[j] != CHAN_DISABLED) {
  511. pwmEnableChannel(group.pwm_drv, j, 0);
  512. }
  513. }
  514. group.dma_handle->unlock();
  515. return true;
  516. #else
  517. return false;
  518. #endif //#ifndef DISABLE_DSHOT
  519. }
  520. /*
  521. setup output mode for a group, using group.current_mode. Used to restore output
  522. after serial operations
  523. */
  524. void RCOutput::set_group_mode(pwm_group &group)
  525. {
  526. if (group.pwm_started) {
  527. pwmStop(group.pwm_drv);
  528. group.pwm_started = false;
  529. }
  530. switch (group.current_mode) {
  531. case MODE_PWM_BRUSHED:
  532. // force zero output initially
  533. for (uint8_t i=0; i<4; i++) {
  534. if (group.chan[i] == CHAN_DISABLED) {
  535. continue;
  536. }
  537. uint8_t chan = chan_offset + group.chan[i];
  538. write(chan, 0);
  539. }
  540. break;
  541. case MODE_NEOPIXEL:
  542. {
  543. const uint32_t rate = protocol_bitrate(group.current_mode);
  544. const uint32_t bit_period = 20;
  545. // configure timer driver for DMAR at requested rate
  546. const uint8_t pad_bits = 50;
  547. const uint8_t bits_per_pixel = 24;
  548. const uint8_t channels_per_group = 4;
  549. const uint16_t neopixel_bit_length = bits_per_pixel * channels_per_group * group.neopixel_nleds + pad_bits;
  550. const uint16_t neopixel_buffer_length = neopixel_bit_length * sizeof(uint32_t);
  551. if (!setup_group_DMA(group, rate, bit_period, true, neopixel_buffer_length)) {
  552. group.current_mode = MODE_PWM_NONE;
  553. break;
  554. }
  555. // calculate min time between pulses
  556. dshot_pulse_time_us = 1000000UL * neopixel_bit_length / rate;
  557. break;
  558. }
  559. case MODE_PWM_DSHOT150 ... MODE_PWM_DSHOT1200: {
  560. const uint32_t rate = protocol_bitrate(group.current_mode);
  561. const uint32_t bit_period = 20;
  562. // configure timer driver for DMAR at requested rate
  563. if (!setup_group_DMA(group, rate, bit_period, true, dshot_buffer_length)) {
  564. group.current_mode = MODE_PWM_NONE;
  565. break;
  566. }
  567. // calculate min time between pulses
  568. dshot_pulse_time_us = 1000000UL * dshot_bit_length / rate;
  569. break;
  570. }
  571. case MODE_PWM_ONESHOT:
  572. case MODE_PWM_ONESHOT125:
  573. // for oneshot we set a period of 0, which results in no pulses till we trigger
  574. group.pwm_cfg.period = 0;
  575. group.rc_frequency = 1;
  576. if (group.pwm_started) {
  577. pwmChangePeriod(group.pwm_drv, group.pwm_cfg.period);
  578. }
  579. break;
  580. case MODE_PWM_NORMAL:
  581. case MODE_PWM_NONE:
  582. // nothing needed
  583. break;
  584. }
  585. set_freq_group(group);
  586. if (group.current_mode != MODE_PWM_NONE &&
  587. !group.pwm_started) {
  588. pwmStart(group.pwm_drv, &group.pwm_cfg);
  589. group.pwm_started = true;
  590. for (uint8_t j=0; j<4; j++) {
  591. if (group.chan[j] != CHAN_DISABLED) {
  592. pwmEnableChannel(group.pwm_drv, j, 0);
  593. }
  594. }
  595. }
  596. }
  597. /*
  598. setup output mode
  599. */
  600. void RCOutput::set_output_mode(uint16_t mask, enum output_mode mode)
  601. {
  602. for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
  603. pwm_group &group = pwm_group_list[i];
  604. if (((group.ch_mask << chan_offset) & mask) == 0) {
  605. // this group is not affected
  606. continue;
  607. }
  608. if (mode_requires_dma(mode) && !group.have_up_dma) {
  609. mode = MODE_PWM_NONE;
  610. }
  611. if (mode > MODE_PWM_NORMAL) {
  612. fast_channel_mask |= group.ch_mask;
  613. }
  614. if (group.current_mode != mode) {
  615. group.current_mode = mode;
  616. set_group_mode(group);
  617. }
  618. }
  619. #if HAL_WITH_IO_MCU
  620. if ((mode == MODE_PWM_ONESHOT ||
  621. mode == MODE_PWM_ONESHOT125) &&
  622. (mask & ((1U<<chan_offset)-1)) &&
  623. AP_BoardConfig::io_enabled()) {
  624. iomcu_oneshot125 = (mode == MODE_PWM_ONESHOT125);
  625. // also setup IO to use a 1Hz frequency, so we only get output
  626. // when we trigger
  627. iomcu.set_freq(io_fast_channel_mask, 1);
  628. return iomcu.set_oneshot_mode();
  629. }
  630. if (mode == MODE_PWM_BRUSHED &&
  631. (mask & ((1U<<chan_offset)-1)) &&
  632. AP_BoardConfig::io_enabled()) {
  633. return iomcu.set_brushed_mode();
  634. }
  635. #endif
  636. }
  637. /*
  638. start corking output
  639. */
  640. void RCOutput::cork(void)
  641. {
  642. corked = true;
  643. #if HAL_WITH_IO_MCU
  644. if (AP_BoardConfig::io_enabled()) {
  645. iomcu.cork();
  646. }
  647. #endif
  648. }
  649. /*
  650. stop corking output
  651. */
  652. void RCOutput::push(void)
  653. {
  654. corked = false;
  655. push_local();
  656. #if HAL_WITH_IO_MCU
  657. if (AP_BoardConfig::io_enabled()) {
  658. iomcu.push();
  659. }
  660. #endif
  661. }
  662. /*
  663. enable sbus output
  664. */
  665. bool RCOutput::enable_px4io_sbus_out(uint16_t rate_hz)
  666. {
  667. #if HAL_WITH_IO_MCU
  668. if (AP_BoardConfig::io_enabled()) {
  669. return iomcu.enable_sbus_out(rate_hz);
  670. }
  671. #endif
  672. return false;
  673. }
  674. /*
  675. trigger output groups for oneshot or dshot modes
  676. */
  677. void RCOutput::trigger_groups(void)
  678. {
  679. if (!chMtxTryLock(&trigger_mutex)) {
  680. return;
  681. }
  682. uint64_t now = AP_HAL::micros64();
  683. if (now < min_pulse_trigger_us) {
  684. // guarantee minimum pulse separation
  685. hal.scheduler->delay_microseconds(min_pulse_trigger_us - now);
  686. }
  687. osalSysLock();
  688. for (uint8_t i = 0; i < NUM_GROUPS; i++) {
  689. pwm_group &group = pwm_group_list[i];
  690. if (irq.waiter) {
  691. // doing serial output, don't send pulses
  692. continue;
  693. }
  694. if (group.current_mode == MODE_PWM_ONESHOT ||
  695. group.current_mode == MODE_PWM_ONESHOT125) {
  696. if (trigger_groupmask & (1U<<i)) {
  697. // this triggers pulse output for a channel group
  698. group.pwm_drv->tim->EGR = STM32_TIM_EGR_UG;
  699. }
  700. }
  701. }
  702. osalSysUnlock();
  703. if (!serial_group) {
  704. for (uint8_t i = 0; i < NUM_GROUPS; i++) {
  705. pwm_group &group = pwm_group_list[i];
  706. if (is_dshot_protocol(group.current_mode)) {
  707. dshot_send(group, false);
  708. }
  709. }
  710. }
  711. /*
  712. calculate time that we are allowed to trigger next pulse
  713. to guarantee at least a 50us gap between pulses
  714. */
  715. min_pulse_trigger_us = AP_HAL::micros64() + trigger_widest_pulse + 50;
  716. chMtxUnlock(&trigger_mutex);
  717. }
  718. /*
  719. periodic timer. This is used for oneshot and dshot modes, plus for
  720. safety switch update
  721. */
  722. void RCOutput::timer_tick(void)
  723. {
  724. safety_update();
  725. uint64_t now = AP_HAL::micros64();
  726. for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
  727. pwm_group &group = pwm_group_list[i];
  728. if (!serial_group &&
  729. is_dshot_protocol(group.current_mode) &&
  730. now - group.last_dmar_send_us > 400) {
  731. // do a blocking send now, to guarantee DShot sends at
  732. // above 1000 Hz. This makes the protocol more reliable on
  733. // long cables, and also keeps some ESCs happy that don't
  734. // like low rates
  735. dshot_send(group, true);
  736. }
  737. }
  738. if (neopixel_pending && chMtxTryLock(&trigger_mutex)) {
  739. neopixel_pending = false;
  740. for (uint8_t j = 0; j < NUM_GROUPS; j++) {
  741. pwm_group &group = pwm_group_list[j];
  742. if (group.current_mode == MODE_NEOPIXEL) {
  743. neopixel_send(group);
  744. }
  745. }
  746. chMtxUnlock(&trigger_mutex);
  747. }
  748. if (min_pulse_trigger_us == 0 ||
  749. serial_group != nullptr) {
  750. return;
  751. }
  752. if (now > min_pulse_trigger_us &&
  753. now - min_pulse_trigger_us > 4000) {
  754. // trigger at a minimum of 250Hz
  755. trigger_groups();
  756. }
  757. }
  758. /*
  759. allocate DMA channel
  760. */
  761. void RCOutput::dma_allocate(Shared_DMA *ctx)
  762. {
  763. for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
  764. pwm_group &group = pwm_group_list[i];
  765. if (group.dma_handle == ctx && group.dma == nullptr) {
  766. chSysLock();
  767. group.dma = dmaStreamAllocI(group.dma_up_stream_id, 10, dma_irq_callback, &group);
  768. chSysUnlock();
  769. #if STM32_DMA_SUPPORTS_DMAMUX
  770. if (group.dma) {
  771. dmaSetRequestSource(group.dma, group.dma_up_channel);
  772. }
  773. #endif
  774. }
  775. }
  776. }
  777. /*
  778. deallocate DMA channel
  779. */
  780. void RCOutput::dma_deallocate(Shared_DMA *ctx)
  781. {
  782. for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
  783. pwm_group &group = pwm_group_list[i];
  784. if (group.dma_handle == ctx && group.dma != nullptr) {
  785. chSysLock();
  786. dmaStreamFreeI(group.dma);
  787. group.dma = nullptr;
  788. chSysUnlock();
  789. }
  790. }
  791. }
  792. /*
  793. create a DSHOT 16 bit packet. Based on prepareDshotPacket from betaflight
  794. */
  795. uint16_t RCOutput::create_dshot_packet(const uint16_t value, bool telem_request)
  796. {
  797. uint16_t packet = (value << 1);
  798. if (telem_request) {
  799. packet |= 1;
  800. }
  801. // compute checksum
  802. uint16_t csum = 0;
  803. uint16_t csum_data = packet;
  804. for (uint8_t i = 0; i < 3; i++) {
  805. csum ^= csum_data;
  806. csum_data >>= 4;
  807. }
  808. csum &= 0xf;
  809. // append checksum
  810. packet = (packet << 4) | csum;
  811. return packet;
  812. }
  813. /*
  814. fill in a DMA buffer for dshot
  815. */
  816. void RCOutput::fill_DMA_buffer_dshot(uint32_t *buffer, uint8_t stride, uint16_t packet, uint16_t clockmul)
  817. {
  818. const uint32_t DSHOT_MOTOR_BIT_0 = 7 * clockmul;
  819. const uint32_t DSHOT_MOTOR_BIT_1 = 14 * clockmul;
  820. uint16_t i = 0;
  821. for (; i < dshot_pre; i++) {
  822. buffer[i * stride] = 0;
  823. }
  824. for (; i < 16 + dshot_pre; i++) {
  825. buffer[i * stride] = (packet & 0x8000) ? DSHOT_MOTOR_BIT_1 : DSHOT_MOTOR_BIT_0;
  826. packet <<= 1;
  827. }
  828. for (; i<dshot_bit_length; i++) {
  829. buffer[i * stride] = 0;
  830. }
  831. }
  832. /*
  833. send a set of DShot packets for a channel group
  834. This call be called in blocking mode from the timer, in which case it waits for the DMA lock.
  835. In normal operation it doesn't wait for the DMA lock.
  836. */
  837. void RCOutput::dshot_send(pwm_group &group, bool blocking)
  838. {
  839. #ifndef DISABLE_DSHOT
  840. if (irq.waiter) {
  841. // doing serial output, don't send DShot pulses
  842. return;
  843. }
  844. if (blocking) {
  845. group.dma_handle->lock();
  846. } else {
  847. if (!group.dma_handle->lock_nonblock()) {
  848. return;
  849. }
  850. }
  851. bool safety_on = hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED;
  852. memset((uint8_t *)group.dma_buffer, 0, dshot_buffer_length);
  853. for (uint8_t i=0; i<4; i++) {
  854. uint8_t chan = group.chan[i];
  855. if (chan != CHAN_DISABLED) {
  856. uint16_t pwm = period[chan];
  857. if (safety_on && !(safety_mask & (1U<<(chan+chan_offset)))) {
  858. // safety is on, overwride pwm
  859. pwm = safe_pwm[chan+chan_offset];
  860. }
  861. const uint16_t chan_mask = (1U<<chan);
  862. if (pwm == 0) {
  863. // no output
  864. continue;
  865. }
  866. pwm = constrain_int16(pwm, 1000, 2000);
  867. uint16_t value = 2 * (pwm - 1000);
  868. if (chan_mask & (reversible_mask>>chan_offset)) {
  869. // this is a DShot-3D output, map so that 1500 PWM is zero throttle reversed
  870. if (value < 1000) {
  871. value = 2000 - value;
  872. } else if (value > 1000) {
  873. value = value - 1000;
  874. } else {
  875. // mid-throttle is off
  876. value = 0;
  877. }
  878. }
  879. if (value != 0) {
  880. // dshot values are from 48 to 2047. Zero means off.
  881. value += 47;
  882. }
  883. bool request_telemetry = (telem_request_mask & chan_mask)?true:false;
  884. uint16_t packet = create_dshot_packet(value, request_telemetry);
  885. if (request_telemetry) {
  886. telem_request_mask &= ~chan_mask;
  887. }
  888. fill_DMA_buffer_dshot(group.dma_buffer + i, 4, packet, group.bit_width_mul);
  889. }
  890. }
  891. // start sending the pulses out
  892. send_pulses_DMAR(group, dshot_buffer_length);
  893. group.last_dmar_send_us = AP_HAL::micros64();
  894. #endif //#ifndef DISABLE_DSHOT
  895. }
  896. /*
  897. send a set of Neopixel packets for a channel group
  898. */
  899. void RCOutput::neopixel_send(pwm_group &group)
  900. {
  901. #ifndef DISABLE_DSHOT
  902. if (irq.waiter || !group.dma_handle->lock_nonblock()) {
  903. // doing serial output, don't send Neopixel pulses
  904. return;
  905. }
  906. // start sending the pulses out
  907. send_pulses_DMAR(group, group.dma_buffer_len);
  908. group.last_dmar_send_us = AP_HAL::micros64();
  909. #endif //#ifndef DISABLE_DSHOT
  910. }
  911. /*
  912. send a series of pulses for a group using DMAR. Pulses must have
  913. been encoded into the group dma_buffer with interleaving for the 4
  914. channels in the group
  915. */
  916. void RCOutput::send_pulses_DMAR(pwm_group &group, uint32_t buffer_length)
  917. {
  918. #ifndef DISABLE_DSHOT
  919. /*
  920. The DMA approach we are using is based on the DMAR method from
  921. betaflight. We use the TIMn_UP DMA channel for the timer, and
  922. setup an interleaved set of pulse durations, with a stride of 4
  923. (for the 4 channels). We use the DMAR register to point the DMA
  924. engine at the 4 CCR registers of the timer, so it fills in the
  925. pulse widths for each timer in turn. This means we only use a
  926. single DMA channel for groups of 4 timer channels. See the "DMA
  927. address for full transfer TIMx_DMAR" section of the
  928. datasheet. Many thanks to the betaflight developers for coming
  929. up with this great method.
  930. */
  931. dmaStreamSetPeripheral(group.dma, &(group.pwm_drv->tim->DMAR));
  932. stm32_cacheBufferFlush(group.dma_buffer, buffer_length);
  933. dmaStreamSetMemory0(group.dma, group.dma_buffer);
  934. dmaStreamSetTransactionSize(group.dma, buffer_length/sizeof(uint32_t));
  935. dmaStreamSetFIFO(group.dma, STM32_DMA_FCR_DMDIS | STM32_DMA_FCR_FTH_FULL);
  936. dmaStreamSetMode(group.dma,
  937. STM32_DMA_CR_CHSEL(group.dma_up_channel) |
  938. STM32_DMA_CR_DIR_M2P | STM32_DMA_CR_PSIZE_WORD | STM32_DMA_CR_MSIZE_WORD |
  939. STM32_DMA_CR_MINC | STM32_DMA_CR_PL(3) |
  940. STM32_DMA_CR_TEIE | STM32_DMA_CR_TCIE);
  941. // setup for 4 burst strided transfers. 0x0D is the register
  942. // address offset of the CCR registers in the timer peripheral
  943. group.pwm_drv->tim->DCR = 0x0D | STM32_TIM_DCR_DBL(3);
  944. dmaStreamEnable(group.dma);
  945. #endif //#ifndef DISABLE_DSHOT
  946. }
  947. /*
  948. unlock DMA channel after a dshot send completes
  949. */
  950. void RCOutput::dma_unlock(void *p)
  951. {
  952. #if STM32_DMA_ADVANCED
  953. pwm_group *group = (pwm_group *)p;
  954. chSysLockFromISR();
  955. group->dma_handle->unlock_from_IRQ();
  956. chSysUnlockFromISR();
  957. #endif
  958. }
  959. /*
  960. DMA interrupt handler. Used to mark DMA completed for DShot
  961. */
  962. void RCOutput::dma_irq_callback(void *p, uint32_t flags)
  963. {
  964. pwm_group *group = (pwm_group *)p;
  965. chSysLockFromISR();
  966. dmaStreamDisable(group->dma);
  967. if (group->in_serial_dma && irq.waiter) {
  968. // tell the waiting process we've done the DMA
  969. chEvtSignalI(irq.waiter, serial_event_mask);
  970. } else {
  971. // this prevents us ever having two dshot pulses too close together
  972. chVTSetI(&group->dma_timeout, chTimeUS2I(dshot_min_gap_us), dma_unlock, p);
  973. }
  974. chSysUnlockFromISR();
  975. }
  976. /*
  977. setup for serial output to an ESC using the given
  978. baudrate. Assumes 1 start bit, 1 stop bit, LSB first and 8
  979. databits. This is used for passthrough ESC configuration and
  980. firmware flashing
  981. While serial output is active normal output to the channel group is
  982. suspended.
  983. */
  984. bool RCOutput::serial_setup_output(uint8_t chan, uint32_t baudrate, uint16_t chanmask)
  985. {
  986. // account for IOMCU channels
  987. chan -= chan_offset;
  988. chanmask >>= chan_offset;
  989. pwm_group *new_serial_group = nullptr;
  990. // find the channel group
  991. for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
  992. pwm_group &group = pwm_group_list[i];
  993. if (group.current_mode == MODE_PWM_BRUSHED) {
  994. // can't do serial output with brushed motors
  995. continue;
  996. }
  997. if (group.ch_mask & (1U<<chan)) {
  998. new_serial_group = &group;
  999. for (uint8_t j=0; j<4; j++) {
  1000. if (group.chan[j] == chan) {
  1001. group.serial.chan = j;
  1002. }
  1003. }
  1004. break;
  1005. }
  1006. }
  1007. if (!new_serial_group) {
  1008. if (serial_group) {
  1009. // shutdown old group
  1010. serial_end();
  1011. }
  1012. return false;
  1013. }
  1014. // setup the groups for serial output. We ask for a bit width of 1, which gets modified by the
  1015. // we setup all groups so they all are setup with the right polarity, and to make switching between
  1016. // channels in blheli pass-thru fast
  1017. for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
  1018. pwm_group &group = pwm_group_list[i];
  1019. if (group.ch_mask & chanmask) {
  1020. if (!setup_group_DMA(group, baudrate, 10, false, dshot_buffer_length)) {
  1021. serial_end();
  1022. return false;
  1023. }
  1024. }
  1025. }
  1026. serial_group = new_serial_group;
  1027. // run the thread doing serial IO at highest priority. This is needed to ensure we don't
  1028. // lose bytes when we switch between output and input
  1029. serial_thread = chThdGetSelfX();
  1030. serial_priority = chThdGetSelfX()->realprio;
  1031. chThdSetPriority(HIGHPRIO);
  1032. // remember the bit period for serial_read_byte()
  1033. serial_group->serial.bit_time_us = 1000000UL / baudrate;
  1034. // remember the thread that set things up. This is also used to
  1035. // mark the group as doing serial output, so normal output is
  1036. // suspended
  1037. irq.waiter = chThdGetSelfX();
  1038. return true;
  1039. }
  1040. /*
  1041. fill in a DMA buffer for a serial byte, assuming 1 start bit and 1 stop bit
  1042. */
  1043. void RCOutput::fill_DMA_buffer_byte(uint32_t *buffer, uint8_t stride, uint8_t b, uint32_t bitval)
  1044. {
  1045. const uint32_t BIT_0 = bitval;
  1046. const uint32_t BIT_1 = 0;
  1047. // start bit
  1048. buffer[0] = BIT_0;
  1049. // stop bit
  1050. buffer[9*stride] = BIT_1;
  1051. // 8 data bits
  1052. for (uint8_t i = 0; i < 8; i++) {
  1053. buffer[(1 + i) * stride] = (b & 1) ? BIT_1 : BIT_0;
  1054. b >>= 1;
  1055. }
  1056. }
  1057. /*
  1058. send one serial byte, blocking call, should be called with the DMA lock held
  1059. */
  1060. bool RCOutput::serial_write_byte(uint8_t b)
  1061. {
  1062. chEvtGetAndClearEvents(serial_event_mask);
  1063. fill_DMA_buffer_byte(serial_group->dma_buffer+serial_group->serial.chan, 4, b, serial_group->bit_width_mul*10);
  1064. serial_group->in_serial_dma = true;
  1065. // start sending the pulses out
  1066. send_pulses_DMAR(*serial_group, 10*4*sizeof(uint32_t));
  1067. // wait for the event
  1068. eventmask_t mask = chEvtWaitAnyTimeout(serial_event_mask, chTimeMS2I(2));
  1069. serial_group->in_serial_dma = false;
  1070. return (mask & serial_event_mask) != 0;
  1071. }
  1072. /*
  1073. send a set of serial bytes, blocking call
  1074. */
  1075. bool RCOutput::serial_write_bytes(const uint8_t *bytes, uint16_t len)
  1076. {
  1077. #if STM32_DMA_ADVANCED
  1078. if (!serial_group) {
  1079. return false;
  1080. }
  1081. serial_group->dma_handle->lock();
  1082. memset(serial_group->dma_buffer, 0, dshot_buffer_length);
  1083. while (len--) {
  1084. if (!serial_write_byte(*bytes++)) {
  1085. serial_group->dma_handle->unlock();
  1086. return false;
  1087. }
  1088. }
  1089. // add a small delay for last word of output to have completely
  1090. // finished
  1091. hal.scheduler->delay_microseconds(25);
  1092. serial_group->dma_handle->unlock();
  1093. return true;
  1094. #else
  1095. return false;
  1096. #endif //#if STM32_DMA_ADVANCED
  1097. }
  1098. /*
  1099. irq handler for bit transition in serial_read_byte()
  1100. This implements a one byte soft serial reader
  1101. */
  1102. void RCOutput::serial_bit_irq(void)
  1103. {
  1104. systime_t now = chVTGetSystemTimeX();
  1105. uint8_t bit = palReadLine(irq.line);
  1106. bool send_signal = false;
  1107. #if RCOU_SERIAL_TIMING_DEBUG
  1108. palWriteLine(HAL_GPIO_LINE_GPIO55, bit);
  1109. #endif
  1110. if (irq.nbits == 0 || bit == irq.last_bit) {
  1111. // start of byte, should be low
  1112. if (bit != 0) {
  1113. irq.byteval = 0x200;
  1114. send_signal = true;
  1115. } else {
  1116. irq.nbits = 1;
  1117. irq.byte_start_tick = now;
  1118. irq.bitmask = 0;
  1119. // setup a timeout for 11 bits width, so we aren't left
  1120. // waiting at the end of bytes
  1121. chSysLockFromISR();
  1122. chVTSetI(&irq.serial_timeout, irq.bit_time_tick*11, serial_byte_timeout, irq.waiter);
  1123. chSysUnlockFromISR();
  1124. }
  1125. } else {
  1126. systime_t dt = now - irq.byte_start_tick;
  1127. uint8_t bitnum = (dt+(irq.bit_time_tick/2)) / irq.bit_time_tick;
  1128. if (bitnum > 10) {
  1129. bitnum = 10;
  1130. }
  1131. if (!bit) {
  1132. // set the bits that we've processed
  1133. irq.bitmask |= ((1U<<bitnum)-1) & ~((1U<<irq.nbits)-1);
  1134. }
  1135. irq.nbits = bitnum;
  1136. if (irq.nbits == 10) {
  1137. send_signal = true;
  1138. irq.byteval = irq.bitmask & 0x3FF;
  1139. irq.bitmask = 0;
  1140. irq.nbits = 1;
  1141. irq.byte_start_tick = now;
  1142. }
  1143. }
  1144. irq.last_bit = bit;
  1145. if (send_signal) {
  1146. chSysLockFromISR();
  1147. chVTResetI(&irq.serial_timeout);
  1148. chEvtSignalI(irq.waiter, serial_event_mask);
  1149. chSysUnlockFromISR();
  1150. }
  1151. }
  1152. /*
  1153. timeout a byte read
  1154. */
  1155. void RCOutput::serial_byte_timeout(void *ctx)
  1156. {
  1157. chSysLockFromISR();
  1158. irq.timed_out = true;
  1159. chEvtSignalI((thread_t *)ctx, serial_event_mask);
  1160. chSysUnlockFromISR();
  1161. }
  1162. /*
  1163. read a byte from a port, using serial parameters from serial_setup_output()
  1164. */
  1165. bool RCOutput::serial_read_byte(uint8_t &b)
  1166. {
  1167. irq.timed_out = false;
  1168. chVTSet(&irq.serial_timeout, chTimeMS2I(10), serial_byte_timeout, irq.waiter);
  1169. bool timed_out = ((chEvtWaitAny(serial_event_mask) & serial_event_mask) == 0) || irq.timed_out;
  1170. uint16_t byteval = irq.byteval;
  1171. if (timed_out) {
  1172. // we can accept a byte with a timeout if the last bit was 1
  1173. // and the start bit is set correctly
  1174. if (irq.last_bit == 0) {
  1175. return false;
  1176. }
  1177. byteval = irq.bitmask | 0x200;
  1178. }
  1179. if ((byteval & 0x201) != 0x200) {
  1180. // wrong start/stop bits
  1181. return false;
  1182. }
  1183. b = uint8_t(byteval>>1);
  1184. return true;
  1185. }
  1186. /*
  1187. read a byte from a port, using serial parameters from serial_setup_output()
  1188. */
  1189. uint16_t RCOutput::serial_read_bytes(uint8_t *buf, uint16_t len)
  1190. {
  1191. #ifndef DISABLE_SERIAL_ESC_COMM
  1192. if (serial_group == nullptr) {
  1193. return 0;
  1194. }
  1195. pwm_group &group = *serial_group;
  1196. const ioline_t line = group.pal_lines[group.serial.chan];
  1197. uint32_t gpio_mode = PAL_MODE_INPUT_PULLUP;
  1198. uint32_t restore_mode = PAL_MODE_ALTERNATE(group.alt_functions[group.serial.chan]) | PAL_STM32_OSPEED_MID2 | PAL_STM32_OTYPE_PUSHPULL;
  1199. uint16_t i = 0;
  1200. #if RCOU_SERIAL_TIMING_DEBUG
  1201. hal.gpio->pinMode(54, 1);
  1202. hal.gpio->pinMode(55, 1);
  1203. #endif
  1204. // assume GPIO mappings for PWM outputs start at 50
  1205. palSetLineMode(line, gpio_mode);
  1206. chVTObjectInit(&irq.serial_timeout);
  1207. chEvtGetAndClearEvents(serial_event_mask);
  1208. irq.line = group.pal_lines[group.serial.chan];
  1209. irq.nbits = 0;
  1210. irq.bitmask = 0;
  1211. irq.byteval = 0;
  1212. irq.bit_time_tick = serial_group->serial.bit_time_us;
  1213. irq.last_bit = 0;
  1214. irq.waiter = chThdGetSelfX();
  1215. #if RCOU_SERIAL_TIMING_DEBUG
  1216. palWriteLine(HAL_GPIO_LINE_GPIO54, 1);
  1217. #endif
  1218. if (!((GPIO *)hal.gpio)->_attach_interrupt(line, serial_bit_irq, AP_HAL::GPIO::INTERRUPT_BOTH)) {
  1219. #if RCOU_SERIAL_TIMING_DEBUG
  1220. palWriteLine(HAL_GPIO_LINE_GPIO54, 0);
  1221. #endif
  1222. return false;
  1223. }
  1224. for (i=0; i<len; i++) {
  1225. if (!serial_read_byte(buf[i])) {
  1226. break;
  1227. }
  1228. }
  1229. ((GPIO *)hal.gpio)->_attach_interrupt(line, nullptr, 0);
  1230. irq.waiter = nullptr;
  1231. palSetLineMode(line, restore_mode);
  1232. #if RCOU_SERIAL_TIMING_DEBUG
  1233. palWriteLine(HAL_GPIO_LINE_GPIO54, 0);
  1234. #endif
  1235. return i;
  1236. #else
  1237. return false;
  1238. #endif //#ifndef DISABLE_SERIAL_ESC_COMM
  1239. }
  1240. /*
  1241. end serial output
  1242. */
  1243. void RCOutput::serial_end(void)
  1244. {
  1245. #ifndef DISABLE_SERIAL_ESC_COMM
  1246. if (serial_group) {
  1247. if (serial_thread == chThdGetSelfX()) {
  1248. chThdSetPriority(serial_priority);
  1249. serial_thread = nullptr;
  1250. }
  1251. irq.waiter = nullptr;
  1252. for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
  1253. pwm_group &group = pwm_group_list[i];
  1254. // restore normal output
  1255. if (group.pwm_started) {
  1256. pwmStop(group.pwm_drv);
  1257. group.pwm_started = false;
  1258. }
  1259. set_group_mode(group);
  1260. set_freq_group(group);
  1261. }
  1262. }
  1263. serial_group = nullptr;
  1264. #endif //#ifndef DISABLE_SERIAL_ESC_COMM
  1265. }
  1266. /*
  1267. get safety switch state for Util.cpp
  1268. */
  1269. AP_HAL::Util::safety_state RCOutput::_safety_switch_state(void)
  1270. {
  1271. #if HAL_WITH_IO_MCU
  1272. if (AP_BoardConfig::io_enabled()) {
  1273. safety_state = iomcu.get_safety_switch_state();
  1274. }
  1275. #endif
  1276. if (!hal.util->was_watchdog_reset()) {
  1277. hal.util->persistent_data.safety_state = safety_state;
  1278. }
  1279. return safety_state;
  1280. }
  1281. /*
  1282. force the safety switch on, disabling PWM output from the IO board
  1283. */
  1284. bool RCOutput::force_safety_on(void)
  1285. {
  1286. #if HAL_WITH_IO_MCU
  1287. if (AP_BoardConfig::io_enabled()) {
  1288. return iomcu.force_safety_on();
  1289. }
  1290. return false;
  1291. #else
  1292. safety_state = AP_HAL::Util::SAFETY_DISARMED;
  1293. return true;
  1294. #endif
  1295. }
  1296. /*
  1297. force the safety switch off, enabling PWM output from the IO board
  1298. */
  1299. void RCOutput::force_safety_off(void)
  1300. {
  1301. #if HAL_WITH_IO_MCU
  1302. if (AP_BoardConfig::io_enabled()) {
  1303. iomcu.force_safety_off();
  1304. }
  1305. #else
  1306. safety_state = AP_HAL::Util::SAFETY_ARMED;
  1307. #endif
  1308. }
  1309. /*
  1310. set PWM to send to a set of channels when the safety switch is
  1311. in the safe state
  1312. */
  1313. void RCOutput::set_safety_pwm(uint32_t chmask, uint16_t period_us)
  1314. {
  1315. #if HAL_WITH_IO_MCU
  1316. if (AP_BoardConfig::io_enabled()) {
  1317. iomcu.set_safety_pwm(chmask, period_us);
  1318. }
  1319. #endif
  1320. for (uint8_t i=0; i<16; i++) {
  1321. if (chmask & (1U<<i)) {
  1322. safe_pwm[i] = period_us;
  1323. }
  1324. }
  1325. }
  1326. /*
  1327. update safety state
  1328. */
  1329. void RCOutput::safety_update(void)
  1330. {
  1331. uint32_t now = AP_HAL::millis();
  1332. if (now - safety_update_ms < 100) {
  1333. // update safety at 10Hz
  1334. return;
  1335. }
  1336. safety_update_ms = now;
  1337. AP_BoardConfig *boardconfig = AP_BoardConfig::get_singleton();
  1338. if (boardconfig) {
  1339. // remember mask of channels to allow with safety on
  1340. safety_mask = boardconfig->get_safety_mask();
  1341. }
  1342. #ifdef HAL_GPIO_PIN_SAFETY_IN
  1343. // handle safety button
  1344. bool safety_pressed = palReadLine(HAL_GPIO_PIN_SAFETY_IN);
  1345. if (safety_pressed) {
  1346. AP_BoardConfig *brdconfig = AP_BoardConfig::get_singleton();
  1347. if (safety_press_count < 255) {
  1348. safety_press_count++;
  1349. }
  1350. if (brdconfig && brdconfig->safety_button_handle_pressed(safety_press_count)) {
  1351. if (safety_state ==AP_HAL::Util::SAFETY_ARMED) {
  1352. safety_state = AP_HAL::Util::SAFETY_DISARMED;
  1353. } else {
  1354. safety_state = AP_HAL::Util::SAFETY_ARMED;
  1355. }
  1356. }
  1357. } else {
  1358. safety_press_count = 0;
  1359. }
  1360. #elif HAL_WITH_IO_MCU
  1361. safety_state = _safety_switch_state();
  1362. iomcu.set_safety_mask(safety_mask);
  1363. #endif
  1364. #ifdef HAL_GPIO_PIN_LED_SAFETY
  1365. led_counter = (led_counter+1) % 16;
  1366. const uint16_t led_pattern = safety_state==AP_HAL::Util::SAFETY_DISARMED?0x5500:0xFFFF;
  1367. palWriteLine(HAL_GPIO_PIN_LED_SAFETY, (led_pattern & (1U << led_counter))?0:1);
  1368. #endif
  1369. }
  1370. /*
  1371. set PWM to send to a set of channels if the FMU firmware dies
  1372. */
  1373. void RCOutput::set_failsafe_pwm(uint32_t chmask, uint16_t period_us)
  1374. {
  1375. #if HAL_WITH_IO_MCU
  1376. if (AP_BoardConfig::io_enabled()) {
  1377. iomcu.set_failsafe_pwm(chmask, period_us);
  1378. }
  1379. #endif
  1380. }
  1381. /*
  1382. true when the output mode is of type dshot
  1383. */
  1384. bool RCOutput::is_dshot_protocol(const enum output_mode mode) const
  1385. {
  1386. switch (mode) {
  1387. case MODE_PWM_DSHOT150:
  1388. case MODE_PWM_DSHOT300:
  1389. case MODE_PWM_DSHOT600:
  1390. case MODE_PWM_DSHOT1200:
  1391. return true;
  1392. default:
  1393. return false;
  1394. }
  1395. }
  1396. /*
  1397. returns the bitrate in Hz of the given output_mode
  1398. */
  1399. uint32_t RCOutput::protocol_bitrate(const enum output_mode mode) const
  1400. {
  1401. switch (mode) {
  1402. case MODE_PWM_DSHOT150:
  1403. return 150000;
  1404. case MODE_PWM_DSHOT300:
  1405. return 300000;
  1406. case MODE_PWM_DSHOT600:
  1407. return 600000;
  1408. case MODE_PWM_DSHOT1200:
  1409. return 1200000;
  1410. case MODE_NEOPIXEL:
  1411. return 800000;
  1412. default:
  1413. // use 1 to prevent a possible divide-by-zero
  1414. return 1;
  1415. }
  1416. }
  1417. /*
  1418. setup neopixel (WS2812B) output for a given channel number, with
  1419. the given max number of LEDs in the chain.
  1420. */
  1421. bool RCOutput::set_neopixel_num_LEDs(const uint16_t chan, uint8_t num_leds)
  1422. {
  1423. uint8_t i;
  1424. pwm_group *grp = find_chan(chan, i);
  1425. if (!grp) {
  1426. return false;
  1427. }
  1428. if (grp->neopixel_nleds == num_leds && grp->current_mode == MODE_NEOPIXEL) {
  1429. // no change
  1430. return true;
  1431. }
  1432. grp->neopixel_nleds = MAX(num_leds, grp->neopixel_nleds);
  1433. set_output_mode(1U<<chan, MODE_NEOPIXEL);
  1434. return grp->current_mode == MODE_NEOPIXEL;
  1435. }
  1436. /*
  1437. setup neopixel (WS2812B) output data for a given output channel
  1438. and mask of LEDs on the channel
  1439. */
  1440. void RCOutput::set_neopixel_rgb_data(const uint16_t chan, uint32_t ledmask, uint8_t red, uint8_t green, uint8_t blue)
  1441. {
  1442. uint8_t i;
  1443. pwm_group *grp = find_chan(chan, i);
  1444. if (!grp) {
  1445. return;
  1446. }
  1447. // mask out for enabled LEDs
  1448. ledmask &= (1U<<grp->neopixel_nleds)-1;
  1449. uint8_t led = 0;
  1450. while (ledmask) {
  1451. if (ledmask & 1) {
  1452. const uint8_t neopixel_bit_length = 24;
  1453. const uint8_t stride = 4;
  1454. uint32_t *buf = grp->dma_buffer + (led * neopixel_bit_length) * stride + i;
  1455. uint32_t bits = (green<<16) | (red<<8) | blue;
  1456. const uint32_t BIT_0 = 7 * grp->bit_width_mul;
  1457. const uint32_t BIT_1 = 14 * grp->bit_width_mul;
  1458. for (uint16_t b=0; b < 24; b++) {
  1459. buf[b * stride] = (bits & 0x800000) ? BIT_1 : BIT_0;
  1460. bits <<= 1;
  1461. }
  1462. }
  1463. ledmask >>= 1;
  1464. led++;
  1465. }
  1466. }
  1467. /*
  1468. trigger send of neopixel data
  1469. */
  1470. void RCOutput::neopixel_send(void)
  1471. {
  1472. neopixel_pending = true;
  1473. }
  1474. #endif // HAL_USE_PWM