AP_BLHeli.cpp 45 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495969798991001011021031041051061071081091101111121131141151161171181191201211221231241251261271281291301311321331341351361371381391401411421431441451461471481491501511521531541551561571581591601611621631641651661671681691701711721731741751761771781791801811821831841851861871881891901911921931941951961971981992002012022032042052062072082092102112122132142152162172182192202212222232242252262272282292302312322332342352362372382392402412422432442452462472482492502512522532542552562572582592602612622632642652662672682692702712722732742752762772782792802812822832842852862872882892902912922932942952962972982993003013023033043053063073083093103113123133143153163173183193203213223233243253263273283293303313323333343353363373383393403413423433443453463473483493503513523533543553563573583593603613623633643653663673683693703713723733743753763773783793803813823833843853863873883893903913923933943953963973983994004014024034044054064074084094104114124134144154164174184194204214224234244254264274284294304314324334344354364374384394404414424434444454464474484494504514524534544554564574584594604614624634644654664674684694704714724734744754764774784794804814824834844854864874884894904914924934944954964974984995005015025035045055065075085095105115125135145155165175185195205215225235245255265275285295305315325335345355365375385395405415425435445455465475485495505515525535545555565575585595605615625635645655665675685695705715725735745755765775785795805815825835845855865875885895905915925935945955965975985996006016026036046056066076086096106116126136146156166176186196206216226236246256266276286296306316326336346356366376386396406416426436446456466476486496506516526536546556566576586596606616626636646656666676686696706716726736746756766776786796806816826836846856866876886896906916926936946956966976986997007017027037047057067077087097107117127137147157167177187197207217227237247257267277287297307317327337347357367377387397407417427437447457467477487497507517527537547557567577587597607617627637647657667677687697707717727737747757767777787797807817827837847857867877887897907917927937947957967977987998008018028038048058068078088098108118128138148158168178188198208218228238248258268278288298308318328338348358368378388398408418428438448458468478488498508518528538548558568578588598608618628638648658668678688698708718728738748758768778788798808818828838848858868878888898908918928938948958968978988999009019029039049059069079089099109119129139149159169179189199209219229239249259269279289299309319329339349359369379389399409419429439449459469479489499509519529539549559569579589599609619629639649659669679689699709719729739749759769779789799809819829839849859869879889899909919929939949959969979989991000100110021003100410051006100710081009101010111012101310141015101610171018101910201021102210231024102510261027102810291030103110321033103410351036103710381039104010411042104310441045104610471048104910501051105210531054105510561057105810591060106110621063106410651066106710681069107010711072107310741075107610771078107910801081108210831084108510861087108810891090109110921093109410951096109710981099110011011102110311041105110611071108110911101111111211131114111511161117111811191120112111221123112411251126112711281129113011311132113311341135113611371138113911401141114211431144114511461147114811491150115111521153115411551156115711581159116011611162116311641165116611671168116911701171117211731174117511761177117811791180118111821183118411851186118711881189119011911192119311941195119611971198119912001201120212031204120512061207120812091210121112121213121412151216121712181219122012211222122312241225122612271228122912301231123212331234123512361237123812391240124112421243124412451246124712481249125012511252125312541255125612571258125912601261126212631264126512661267126812691270127112721273127412751276127712781279128012811282128312841285128612871288128912901291129212931294129512961297129812991300130113021303130413051306130713081309131013111312131313141315131613171318131913201321132213231324132513261327132813291330133113321333133413351336133713381339134013411342134313441345134613471348134913501351135213531354135513561357135813591360136113621363136413651366136713681369137013711372137313741375137613771378137913801381138213831384138513861387138813891390139113921393139413951396139713981399140014011402140314041405140614071408140914101411141214131414141514161417141814191420142114221423142414251426142714281429143014311432143314341435143614371438143914401441144214431444144514461447144814491450145114521453145414551456145714581459146014611462146314641465146614671468146914701471147214731474147514761477147814791480
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. /*
  14. implementation of MSP and BLHeli-4way protocols for pass-through ESC
  15. calibration and firmware update
  16. With thanks to betaflight for a great reference
  17. implementation. Several of the functions below are based on
  18. betaflight equivalent functions
  19. */
  20. #include "AP_BLHeli.h"
  21. #ifdef HAVE_AP_BLHELI_SUPPORT
  22. #include <AP_Math/crc.h>
  23. #include <AP_Motors/AP_Motors_Class.h>
  24. #include <GCS_MAVLink/GCS_MAVLink.h>
  25. #include <GCS_MAVLink/GCS.h>
  26. #include <AP_SerialManager/AP_SerialManager.h>
  27. #include <AP_Logger/AP_Logger.h>
  28. extern const AP_HAL::HAL& hal;
  29. #define debug(fmt, args ...) do { if (debug_level) { gcs().send_text(MAV_SEVERITY_INFO, "ESC: " fmt, ## args); } } while (0)
  30. // key for locking UART for exclusive use. This prevents any other writes from corrupting
  31. // the MSP protocol on hal.console
  32. #define BLHELI_UART_LOCK_KEY 0x20180402
  33. const AP_Param::GroupInfo AP_BLHeli::var_info[] = {
  34. // @Param: MASK
  35. // @DisplayName: BLHeli Channel Bitmask
  36. // @Description: Enable of BLHeli pass-thru servo protocol support to specific channels. This mask is in addition to motors enabled using SERVO_BLH_AUTO (if any)
  37. // @Bitmask: 0:Channel1,1:Channel2,2:Channel3,3:Channel4,4:Channel5,5:Channel6,6:Channel7,7:Channel8,8:Channel9,9:Channel10,10:Channel11,11:Channel12,12:Channel13,13:Channel14,14:Channel15,15:Channel16
  38. // @User: Advanced
  39. AP_GROUPINFO("MASK", 1, AP_BLHeli, channel_mask, 0),
  40. #if APM_BUILD_TYPE(APM_BUILD_ArduCopter) || APM_BUILD_TYPE(APM_BUILD_ArduPlane)
  41. // @Param: AUTO
  42. // @DisplayName: BLHeli auto-enable for multicopter motors
  43. // @Description: If set to 1 this auto-enables BLHeli pass-thru support for all multicopter motors
  44. // @Values: 0:Disabled,1:Enabled
  45. // @User: Standard
  46. AP_GROUPINFO("AUTO", 2, AP_BLHeli, channel_auto, 0),
  47. #endif
  48. // @Param: TEST
  49. // @DisplayName: BLHeli internal interface test
  50. // @Description: Setting SERVO_BLH_TEST to a motor number enables an internal test of the BLHeli ESC protocol to the corresponding ESC. The debug output is displayed on the USB console.
  51. // @Values: 0:Disabled,1:TestMotor1,2:TestMotor2,3:TestMotor3,4:TestMotor4,5:TestMotor5,6:TestMotor6,7:TestMotor7,8:TestMotor8
  52. // @User: Advanced
  53. AP_GROUPINFO("TEST", 3, AP_BLHeli, run_test, 0),
  54. // @Param: TMOUT
  55. // @DisplayName: BLHeli protocol timeout
  56. // @Description: This sets the inactivity timeout for the BLHeli protocol in seconds. If no packets are received in this time normal MAVLink operations are resumed. A value of 0 means no timeout
  57. // @Units: s
  58. // @Range: 0 300
  59. // @User: Standard
  60. AP_GROUPINFO("TMOUT", 4, AP_BLHeli, timeout_sec, 0),
  61. // @Param: TRATE
  62. // @DisplayName: BLHeli telemetry rate
  63. // @Description: This sets the rate in Hz for requesting telemetry from ESCs. It is the rate per ESC. Setting to zero disables telemetry requests
  64. // @Units: Hz
  65. // @Range: 0 500
  66. // @User: Standard
  67. AP_GROUPINFO("TRATE", 5, AP_BLHeli, telem_rate, 10),
  68. // @Param: DEBUG
  69. // @DisplayName: BLHeli debug level
  70. // @Description: When set to 1 this enabled verbose debugging output over MAVLink when the blheli protocol is active. This can be used to diagnose failures.
  71. // @Values: 0:Disabled,1:Enabled
  72. // @User: Standard
  73. AP_GROUPINFO("DEBUG", 6, AP_BLHeli, debug_level, 0),
  74. // @Param: OTYPE
  75. // @DisplayName: BLHeli output type override
  76. // @Description: When set to a non-zero value this overrides the output type for the output channels given by SERVO_BLH_MASK. This can be used to enable DShot on outputs that are not part of the multicopter motors group.
  77. // @Values: 0:None,1:OneShot,2:OneShot125,3:Brushed,4:DShot150,5:DShot300,6:DShot600,7:DShot1200
  78. // @User: Advanced
  79. AP_GROUPINFO("OTYPE", 7, AP_BLHeli, output_type, 0),
  80. // @Param: PORT
  81. // @DisplayName: Control port
  82. // @Description: This sets the telemetry port to use for blheli pass-thru
  83. // @Values: 0:Console,1:Telem1,2:Telem2,3:Telem3,4:Telem4,5:Telem5
  84. // @User: Advanced
  85. AP_GROUPINFO("PORT", 8, AP_BLHeli, control_port, 0),
  86. // @Param: POLES
  87. // @DisplayName: BLHeli Motor Poles
  88. // @Description: This allows calculation of true RPM from ESC's eRPM. The default is 14.
  89. // @Range: 1 127
  90. // @User: Advanced
  91. AP_GROUPINFO("POLES", 9, AP_BLHeli, motor_poles, 14),
  92. // @Param: REMASK
  93. // @DisplayName: BLHeli bitmask of reversible channels
  94. // @Description: Mask of channels which are reversible. This is used for ESCs which have been configured in '3D' mode, allowing for the motor to spin in either direction
  95. // @Bitmask: 0:Channel1,1:Channel2,2:Channel3,3:Channel4,4:Channel5,5:Channel6,6:Channel7,7:Channel8,8:Channel9,9:Channel10,10:Channel11,11:Channel12,12:Channel13,13:Channel14,14:Channel15,15:Channel16
  96. // @User: Advanced
  97. AP_GROUPINFO("REMASK", 10, AP_BLHeli, channel_reversible_mask, 0),
  98. AP_GROUPEND
  99. };
  100. AP_BLHeli *AP_BLHeli::_singleton;
  101. // constructor
  102. AP_BLHeli::AP_BLHeli(void)
  103. {
  104. // set defaults from the parameter table
  105. AP_Param::setup_object_defaults(this, var_info);
  106. _singleton = this;
  107. last_control_port = -1;
  108. }
  109. /*
  110. process one byte of serial input for MSP protocol
  111. */
  112. bool AP_BLHeli::msp_process_byte(uint8_t c)
  113. {
  114. if (msp.state == MSP_IDLE) {
  115. msp.escMode = PROTOCOL_NONE;
  116. if (c == '$') {
  117. msp.state = MSP_HEADER_START;
  118. } else {
  119. return false;
  120. }
  121. } else if (msp.state == MSP_HEADER_START) {
  122. msp.state = (c == 'M') ? MSP_HEADER_M : MSP_IDLE;
  123. } else if (msp.state == MSP_HEADER_M) {
  124. msp.state = MSP_IDLE;
  125. switch (c) {
  126. case '<': // COMMAND
  127. msp.packetType = MSP_PACKET_COMMAND;
  128. msp.state = MSP_HEADER_ARROW;
  129. break;
  130. case '>': // REPLY
  131. msp.packetType = MSP_PACKET_REPLY;
  132. msp.state = MSP_HEADER_ARROW;
  133. break;
  134. default:
  135. break;
  136. }
  137. } else if (msp.state == MSP_HEADER_ARROW) {
  138. if (c > sizeof(msp.buf)) {
  139. msp.state = MSP_IDLE;
  140. } else {
  141. msp.dataSize = c;
  142. msp.offset = 0;
  143. msp.checksum = 0;
  144. msp.checksum ^= c;
  145. msp.state = MSP_HEADER_SIZE;
  146. }
  147. } else if (msp.state == MSP_HEADER_SIZE) {
  148. msp.cmdMSP = c;
  149. msp.checksum ^= c;
  150. msp.state = MSP_HEADER_CMD;
  151. } else if (msp.state == MSP_HEADER_CMD && msp.offset < msp.dataSize) {
  152. msp.checksum ^= c;
  153. msp.buf[msp.offset++] = c;
  154. } else if (msp.state == MSP_HEADER_CMD && msp.offset >= msp.dataSize) {
  155. if (msp.checksum == c) {
  156. msp.state = MSP_COMMAND_RECEIVED;
  157. } else {
  158. msp.state = MSP_IDLE;
  159. }
  160. }
  161. return true;
  162. }
  163. /*
  164. update CRC state for blheli protocol
  165. */
  166. void AP_BLHeli::blheli_crc_update(uint8_t c)
  167. {
  168. blheli.crc = crc_xmodem_update(blheli.crc, c);
  169. }
  170. /*
  171. process one byte of serial input for blheli 4way protocol
  172. */
  173. bool AP_BLHeli::blheli_4way_process_byte(uint8_t c)
  174. {
  175. if (blheli.state == BLHELI_IDLE) {
  176. if (c == cmd_Local_Escape) {
  177. blheli.state = BLHELI_HEADER_START;
  178. blheli.crc = 0;
  179. blheli_crc_update(c);
  180. } else {
  181. return false;
  182. }
  183. } else if (blheli.state == BLHELI_HEADER_START) {
  184. blheli.command = c;
  185. blheli_crc_update(c);
  186. blheli.state = BLHELI_HEADER_CMD;
  187. } else if (blheli.state == BLHELI_HEADER_CMD) {
  188. blheli.address = c<<8;
  189. blheli.state = BLHELI_HEADER_ADDR_HIGH;
  190. blheli_crc_update(c);
  191. } else if (blheli.state == BLHELI_HEADER_ADDR_HIGH) {
  192. blheli.address |= c;
  193. blheli.state = BLHELI_HEADER_ADDR_LOW;
  194. blheli_crc_update(c);
  195. } else if (blheli.state == BLHELI_HEADER_ADDR_LOW) {
  196. blheli.state = BLHELI_HEADER_LEN;
  197. blheli.param_len = c?c:256;
  198. blheli.offset = 0;
  199. blheli_crc_update(c);
  200. } else if (blheli.state == BLHELI_HEADER_LEN) {
  201. blheli.buf[blheli.offset++] = c;
  202. blheli_crc_update(c);
  203. if (blheli.offset == blheli.param_len) {
  204. blheli.state = BLHELI_CRC1;
  205. }
  206. } else if (blheli.state == BLHELI_CRC1) {
  207. blheli.crc1 = c;
  208. blheli.state = BLHELI_CRC2;
  209. } else if (blheli.state == BLHELI_CRC2) {
  210. uint16_t crc = blheli.crc1<<8 | c;
  211. if (crc == blheli.crc) {
  212. blheli.state = BLHELI_COMMAND_RECEIVED;
  213. } else {
  214. blheli.state = BLHELI_IDLE;
  215. }
  216. }
  217. return true;
  218. }
  219. /*
  220. send a MSP protocol reply
  221. */
  222. void AP_BLHeli::msp_send_reply(uint8_t cmd, const uint8_t *buf, uint8_t len)
  223. {
  224. uint8_t *b = &msp.buf[0];
  225. *b++ = '$';
  226. *b++ = 'M';
  227. *b++ = '>';
  228. *b++ = len;
  229. *b++ = cmd;
  230. memcpy(b, buf, len);
  231. b += len;
  232. uint8_t c = 0;
  233. for (uint8_t i=0; i<len+2; i++) {
  234. c ^= msp.buf[i+3];
  235. }
  236. *b++ = c;
  237. uart->write_locked(&msp.buf[0], len+6, BLHELI_UART_LOCK_KEY);
  238. }
  239. void AP_BLHeli::putU16(uint8_t *b, uint16_t v)
  240. {
  241. b[0] = v;
  242. b[1] = v >> 8;
  243. }
  244. uint16_t AP_BLHeli::getU16(const uint8_t *b)
  245. {
  246. return b[0] | (b[1]<<8);
  247. }
  248. void AP_BLHeli::putU32(uint8_t *b, uint32_t v)
  249. {
  250. b[0] = v;
  251. b[1] = v >> 8;
  252. b[2] = v >> 16;
  253. b[3] = v >> 24;
  254. }
  255. void AP_BLHeli::putU16_BE(uint8_t *b, uint16_t v)
  256. {
  257. b[0] = v >> 8;
  258. b[1] = v;
  259. }
  260. /*
  261. process a MSP command from GCS
  262. */
  263. void AP_BLHeli::msp_process_command(void)
  264. {
  265. debug("MSP cmd %u len=%u", msp.cmdMSP, msp.dataSize);
  266. switch (msp.cmdMSP) {
  267. case MSP_API_VERSION: {
  268. debug("MSP_API_VERSION");
  269. uint8_t buf[3] = { MSP_PROTOCOL_VERSION, API_VERSION_MAJOR, API_VERSION_MINOR };
  270. msp_send_reply(msp.cmdMSP, buf, sizeof(buf));
  271. break;
  272. }
  273. case MSP_FC_VARIANT:
  274. debug("MSP_FC_VARIANT");
  275. msp_send_reply(msp.cmdMSP, (const uint8_t *)ARDUPILOT_IDENTIFIER, FLIGHT_CONTROLLER_IDENTIFIER_LENGTH);
  276. break;
  277. case MSP_FC_VERSION: {
  278. debug("MSP_FC_VERSION");
  279. uint8_t version[3] = { 3, 3, 0 };
  280. msp_send_reply(msp.cmdMSP, version, sizeof(version));
  281. break;
  282. }
  283. case MSP_BOARD_INFO: {
  284. debug("MSP_BOARD_INFO");
  285. // send a generic 'ArduPilot ChibiOS' board type
  286. uint8_t buf[7] = { 'A', 'R', 'C', 'H', 0, 0, 0 };
  287. msp_send_reply(msp.cmdMSP, buf, sizeof(buf));
  288. break;
  289. }
  290. case MSP_BUILD_INFO: {
  291. debug("MSP_BUILD_INFO");
  292. // build date, build time, git version
  293. uint8_t buf[26] {
  294. 0x4d, 0x61, 0x72, 0x20, 0x31, 0x36, 0x20, 0x32, 0x30,
  295. 0x31, 0x38, 0x30, 0x38, 0x3A, 0x34, 0x32, 0x3a, 0x32, 0x39,
  296. 0x62, 0x30, 0x66, 0x66, 0x39, 0x32, 0x38};
  297. msp_send_reply(msp.cmdMSP, buf, sizeof(buf));
  298. break;
  299. }
  300. case MSP_REBOOT:
  301. debug("MSP: ignoring reboot command");
  302. break;
  303. case MSP_UID:
  304. // MCU identifer
  305. debug("MSP_UID");
  306. msp_send_reply(msp.cmdMSP, (const uint8_t *)UDID_START, 12);
  307. break;
  308. case MSP_ADVANCED_CONFIG: {
  309. debug("MSP_ADVANCED_CONFIG");
  310. uint8_t buf[10];
  311. buf[0] = 1; // gyro sync denom
  312. buf[1] = 4; // pid process denom
  313. buf[2] = 0; // use unsynced pwm
  314. buf[3] = (uint8_t)PWM_TYPE_DSHOT150; // motor PWM protocol
  315. putU16(&buf[4], 480); // motor PWM Rate
  316. putU16(&buf[6], 450); // idle offset value
  317. buf[8] = 0; // use 32kHz
  318. buf[9] = 0; // motor PWM inversion
  319. msp_send_reply(msp.cmdMSP, buf, sizeof(buf));
  320. break;
  321. }
  322. case MSP_FEATURE_CONFIG: {
  323. debug("MSP_FEATURE_CONFIG");
  324. uint8_t buf[4];
  325. putU32(buf, 0); // from MSPFeatures enum
  326. msp_send_reply(msp.cmdMSP, buf, sizeof(buf));
  327. break;
  328. }
  329. case MSP_STATUS: {
  330. debug("MSP_STATUS");
  331. uint8_t buf[21];
  332. putU16(&buf[0], 1000); // loop time usec
  333. putU16(&buf[2], 0); // i2c error count
  334. putU16(&buf[4], 0x27); // available sensors
  335. putU32(&buf[6], 0); // flight modes
  336. buf[10] = 0; // pid profile index
  337. putU16(&buf[11], 5); // system load percent
  338. putU16(&buf[13], 0); // gyro cycle time
  339. buf[15] = 0; // flight mode flags length
  340. buf[16] = 18; // arming disable flags count
  341. putU32(&buf[17], 0); // arming disable flags
  342. msp_send_reply(msp.cmdMSP, buf, sizeof(buf));
  343. break;
  344. }
  345. case MSP_MOTOR_3D_CONFIG: {
  346. debug("MSP_MOTOR_3D_CONFIG");
  347. uint8_t buf[6];
  348. putU16(&buf[0], 1406); // 3D deadband low
  349. putU16(&buf[2], 1514); // 3D deadband high
  350. putU16(&buf[4], 1460); // 3D neutral
  351. msp_send_reply(msp.cmdMSP, buf, sizeof(buf));
  352. break;
  353. }
  354. case MSP_MOTOR_CONFIG: {
  355. debug("MSP_MOTOR_CONFIG");
  356. uint8_t buf[6];
  357. putU16(&buf[0], 1030); // min throttle
  358. putU16(&buf[2], 2000); // max throttle
  359. putU16(&buf[4], 1000); // min command
  360. msp_send_reply(msp.cmdMSP, buf, sizeof(buf));
  361. break;
  362. }
  363. case MSP_MOTOR: {
  364. debug("MSP_MOTOR");
  365. // get the output going to each motor
  366. uint8_t buf[16] {};
  367. for (uint8_t i = 0; i < num_motors; i++) {
  368. uint16_t v = hal.rcout->read(motor_map[i]);
  369. putU16(&buf[2*i], v);
  370. }
  371. msp_send_reply(msp.cmdMSP, buf, sizeof(buf));
  372. break;
  373. }
  374. case MSP_SET_MOTOR: {
  375. debug("MSP_SET_MOTOR");
  376. // set the output to each motor
  377. uint8_t nmotors = msp.dataSize / 2;
  378. debug("MSP_SET_MOTOR %u", nmotors);
  379. SRV_Channels::set_disabled_channel_mask(0xFFFF);
  380. motors_disabled = true;
  381. hal.rcout->cork();
  382. for (uint8_t i = 0; i < nmotors; i++) {
  383. if (i >= num_motors) {
  384. break;
  385. }
  386. uint16_t v = getU16(&msp.buf[i*2]);
  387. debug("MSP_SET_MOTOR %u %u", i, v);
  388. // map from a MSP value to a value in the range 1000 to 2000
  389. uint16_t pwm = (v < 1000)?0:v;
  390. hal.rcout->write(motor_map[i], pwm);
  391. }
  392. hal.rcout->push();
  393. break;
  394. }
  395. case MSP_SET_4WAY_IF: {
  396. debug("MSP_SET_4WAY_IF");
  397. if (msp.dataSize == 0) {
  398. msp.escMode = PROTOCOL_4WAY;
  399. } else if (msp.dataSize == 2) {
  400. msp.escMode = (enum escProtocol)msp.buf[0];
  401. msp.portIndex = msp.buf[1];
  402. }
  403. debug("escMode=%u portIndex=%u num_motors=%u", msp.escMode, msp.portIndex, num_motors);
  404. uint8_t n = num_motors;
  405. switch (msp.escMode) {
  406. case PROTOCOL_4WAY:
  407. break;
  408. default:
  409. n = 0;
  410. hal.rcout->serial_end();
  411. serial_start_ms = 0;
  412. break;
  413. }
  414. msp_send_reply(msp.cmdMSP, &n, 1);
  415. break;
  416. }
  417. default:
  418. debug("Unknown MSP command %u", msp.cmdMSP);
  419. break;
  420. }
  421. }
  422. /*
  423. send a blheli 4way protocol reply
  424. */
  425. void AP_BLHeli::blheli_send_reply(const uint8_t *buf, uint16_t len)
  426. {
  427. uint8_t *b = &blheli.buf[0];
  428. *b++ = cmd_Remote_Escape;
  429. *b++ = blheli.command;
  430. putU16_BE(b, blheli.address); b += 2;
  431. *b++ = len==256?0:len;
  432. memcpy(b, buf, len);
  433. b += len;
  434. *b++ = blheli.ack;
  435. putU16_BE(b, crc_xmodem(&blheli.buf[0], len+6));
  436. uart->write_locked(&blheli.buf[0], len+8, BLHELI_UART_LOCK_KEY);
  437. debug("OutB(%u) 0x%02x ack=0x%02x", len+8, (unsigned)blheli.command, blheli.ack);
  438. }
  439. /*
  440. CRC used when talking to ESCs
  441. */
  442. uint16_t AP_BLHeli::BL_CRC(const uint8_t *buf, uint16_t len)
  443. {
  444. uint16_t crc = 0;
  445. while (len--) {
  446. uint8_t xb = *buf++;
  447. for (uint8_t i = 0; i < 8; i++) {
  448. if (((xb & 0x01) ^ (crc & 0x0001)) !=0 ) {
  449. crc = crc >> 1;
  450. crc = crc ^ 0xA001;
  451. } else {
  452. crc = crc >> 1;
  453. }
  454. xb = xb >> 1;
  455. }
  456. }
  457. return crc;
  458. }
  459. bool AP_BLHeli::isMcuConnected(void)
  460. {
  461. return blheli.connected[blheli.chan];
  462. }
  463. void AP_BLHeli::setDisconnected(void)
  464. {
  465. blheli.connected[blheli.chan] = false;
  466. blheli.deviceInfo[blheli.chan][0] = 0;
  467. blheli.deviceInfo[blheli.chan][1] = 0;
  468. }
  469. /*
  470. send a set of bytes to an RC output channel
  471. */
  472. bool AP_BLHeli::BL_SendBuf(const uint8_t *buf, uint16_t len)
  473. {
  474. bool send_crc = isMcuConnected();
  475. if (blheli.chan >= num_motors) {
  476. return false;
  477. }
  478. if (!hal.rcout->serial_setup_output(motor_map[blheli.chan], 19200, motor_mask)) {
  479. blheli.ack = ACK_D_GENERAL_ERROR;
  480. return false;
  481. }
  482. if (serial_start_ms == 0) {
  483. serial_start_ms = AP_HAL::millis();
  484. }
  485. uint32_t now = AP_HAL::millis();
  486. if (serial_start_ms == 0 || now - serial_start_ms < 1000) {
  487. /*
  488. we've just started the interface. We want it idle for at
  489. least 1 second before we start sending serial data.
  490. */
  491. hal.scheduler->delay(1100);
  492. }
  493. memcpy(blheli.buf, buf, len);
  494. uint16_t crc = BL_CRC(buf, len);
  495. blheli.buf[len] = crc;
  496. blheli.buf[len+1] = crc>>8;
  497. if (!hal.rcout->serial_write_bytes(blheli.buf, len+(send_crc?2:0))) {
  498. blheli.ack = ACK_D_GENERAL_ERROR;
  499. return false;
  500. }
  501. return true;
  502. }
  503. /*
  504. read bytes from the ESC connection
  505. */
  506. bool AP_BLHeli::BL_ReadBuf(uint8_t *buf, uint16_t len)
  507. {
  508. bool check_crc = isMcuConnected() && len > 0;
  509. uint16_t req_bytes = len+(check_crc?3:1);
  510. uint16_t n = hal.rcout->serial_read_bytes(blheli.buf, req_bytes);
  511. debug("BL_ReadBuf %u -> %u", len, n);
  512. if (req_bytes != n) {
  513. debug("short read");
  514. blheli.ack = ACK_D_GENERAL_ERROR;
  515. return false;
  516. }
  517. if (check_crc) {
  518. uint16_t crc = BL_CRC(blheli.buf, len);
  519. if ((crc & 0xff) != blheli.buf[len] ||
  520. (crc >> 8) != blheli.buf[len+1]) {
  521. debug("bad CRC");
  522. blheli.ack = ACK_D_GENERAL_ERROR;
  523. return false;
  524. }
  525. if (blheli.buf[len+2] != brSUCCESS) {
  526. debug("bad ACK 0x%02x", blheli.buf[len+2]);
  527. blheli.ack = ACK_D_GENERAL_ERROR;
  528. return false;
  529. }
  530. } else {
  531. if (blheli.buf[len] != brSUCCESS) {
  532. debug("bad ACK1 0x%02x", blheli.buf[len]);
  533. blheli.ack = ACK_D_GENERAL_ERROR;
  534. return false;
  535. }
  536. }
  537. if (len > 0) {
  538. memcpy(buf, blheli.buf, len);
  539. }
  540. return true;
  541. }
  542. uint8_t AP_BLHeli::BL_GetACK(uint16_t timeout_ms)
  543. {
  544. uint8_t ack;
  545. uint32_t start_ms = AP_HAL::millis();
  546. while (AP_HAL::millis() - start_ms < timeout_ms) {
  547. if (hal.rcout->serial_read_bytes(&ack, 1) == 1) {
  548. return ack;
  549. }
  550. }
  551. // return brNONE, meaning no ACK received in the timeout
  552. return brNONE;
  553. }
  554. bool AP_BLHeli::BL_SendCMDSetAddress()
  555. {
  556. // skip if adr == 0xFFFF
  557. if (blheli.address == 0xFFFF) {
  558. return true;
  559. }
  560. debug("BL_SendCMDSetAddress 0x%04x", blheli.address);
  561. uint8_t sCMD[] = {CMD_SET_ADDRESS, 0, uint8_t(blheli.address>>8), uint8_t(blheli.address)};
  562. if (!BL_SendBuf(sCMD, 4)) {
  563. return false;
  564. }
  565. return BL_GetACK() == brSUCCESS;
  566. }
  567. bool AP_BLHeli::BL_ReadA(uint8_t cmd, uint8_t *buf, uint16_t n)
  568. {
  569. if (BL_SendCMDSetAddress()) {
  570. uint8_t sCMD[] = {cmd, uint8_t(n==256?0:n)};
  571. if (!BL_SendBuf(sCMD, 2)) {
  572. return false;
  573. }
  574. bool ret = BL_ReadBuf(buf, n);
  575. if (ret && n == sizeof(esc_status) && blheli.address == esc_status_addr) {
  576. // display esc_status structure if we see it
  577. struct esc_status status;
  578. memcpy(&status, buf, n);
  579. debug("Prot %u Good %u Bad %u %x %x %x x%x\n",
  580. (unsigned)status.protocol,
  581. (unsigned)status.good_frames,
  582. (unsigned)status.bad_frames,
  583. (unsigned)status.unknown[0],
  584. (unsigned)status.unknown[1],
  585. (unsigned)status.unknown[2],
  586. (unsigned)status.unknown2);
  587. }
  588. return ret;
  589. }
  590. return false;
  591. }
  592. /*
  593. connect to a blheli ESC
  594. */
  595. bool AP_BLHeli::BL_ConnectEx(void)
  596. {
  597. if (blheli.connected[blheli.chan] != 0) {
  598. debug("Using cached interface 0x%x for %u", blheli.interface_mode[blheli.chan], blheli.chan);
  599. return true;
  600. }
  601. debug("BL_ConnectEx %u/%u at %u", blheli.chan, num_motors, motor_map[blheli.chan]);
  602. setDisconnected();
  603. const uint8_t BootInit[] = {0,0,0,0,0,0,0,0,0,0,0,0,0x0D,'B','L','H','e','l','i',0xF4,0x7D};
  604. if (!BL_SendBuf(BootInit, 21)) {
  605. return false;
  606. }
  607. uint8_t BootInfo[8];
  608. if (!BL_ReadBuf(BootInfo, 8)) {
  609. return false;
  610. }
  611. // reply must start with 471
  612. if (strncmp((const char *)BootInfo, "471", 3) != 0) {
  613. blheli.ack = ACK_D_GENERAL_ERROR;
  614. return false;
  615. }
  616. // extract device information
  617. blheli.deviceInfo[blheli.chan][2] = BootInfo[3];
  618. blheli.deviceInfo[blheli.chan][1] = BootInfo[4];
  619. blheli.deviceInfo[blheli.chan][0] = BootInfo[5];
  620. blheli.interface_mode[blheli.chan] = 0;
  621. uint16_t *devword = (uint16_t *)blheli.deviceInfo[blheli.chan];
  622. switch (*devword) {
  623. case 0x9307:
  624. case 0x930A:
  625. case 0x930F:
  626. case 0x940B:
  627. blheli.interface_mode[blheli.chan] = imATM_BLB;
  628. debug("Interface type imATM_BLB");
  629. break;
  630. case 0xF310:
  631. case 0xF330:
  632. case 0xF410:
  633. case 0xF390:
  634. case 0xF850:
  635. case 0xE8B1:
  636. case 0xE8B2:
  637. blheli.interface_mode[blheli.chan] = imSIL_BLB;
  638. debug("Interface type imSIL_BLB");
  639. break;
  640. case 0x1F06:
  641. case 0x3306:
  642. case 0x3406:
  643. case 0x3506:
  644. case 0x2B06:
  645. case 0x4706:
  646. blheli.interface_mode[blheli.chan] = imARM_BLB;
  647. debug("Interface type imARM_BLB");
  648. break;
  649. default:
  650. blheli.ack = ACK_D_GENERAL_ERROR;
  651. debug("Unknown interface type 0x%04x", *devword);
  652. break;
  653. }
  654. blheli.deviceInfo[blheli.chan][3] = blheli.interface_mode[blheli.chan];
  655. if (blheli.interface_mode[blheli.chan] != 0) {
  656. blheli.connected[blheli.chan] = true;
  657. }
  658. return true;
  659. }
  660. bool AP_BLHeli::BL_SendCMDKeepAlive(void)
  661. {
  662. uint8_t sCMD[] = {CMD_KEEP_ALIVE, 0};
  663. if (!BL_SendBuf(sCMD, 2)) {
  664. return false;
  665. }
  666. if (BL_GetACK() != brERRORCOMMAND) {
  667. return false;
  668. }
  669. return true;
  670. }
  671. bool AP_BLHeli::BL_PageErase(void)
  672. {
  673. if (BL_SendCMDSetAddress()) {
  674. uint8_t sCMD[] = {CMD_ERASE_FLASH, 0x01};
  675. if (!BL_SendBuf(sCMD, 2)) {
  676. return false;
  677. }
  678. return BL_GetACK(3000) == brSUCCESS;
  679. }
  680. return false;
  681. }
  682. void AP_BLHeli::BL_SendCMDRunRestartBootloader(void)
  683. {
  684. uint8_t sCMD[] = {RestartBootloader, 0};
  685. blheli.deviceInfo[blheli.chan][0] = 1;
  686. BL_SendBuf(sCMD, 2);
  687. }
  688. uint8_t AP_BLHeli::BL_SendCMDSetBuffer(const uint8_t *buf, uint16_t nbytes)
  689. {
  690. uint8_t sCMD[] = {CMD_SET_BUFFER, 0, uint8_t(nbytes>>8), uint8_t(nbytes&0xff)};
  691. if (!BL_SendBuf(sCMD, 4)) {
  692. return false;
  693. }
  694. uint8_t ack;
  695. if ((ack = BL_GetACK()) != brNONE) {
  696. debug("BL_SendCMDSetBuffer ack failed 0x%02x", ack);
  697. blheli.ack = ACK_D_GENERAL_ERROR;
  698. return false;
  699. }
  700. if (!BL_SendBuf(buf, nbytes)) {
  701. debug("BL_SendCMDSetBuffer send failed");
  702. blheli.ack = ACK_D_GENERAL_ERROR;
  703. return false;
  704. }
  705. return (BL_GetACK(40) == brSUCCESS);
  706. }
  707. bool AP_BLHeli::BL_WriteA(uint8_t cmd, const uint8_t *buf, uint16_t nbytes, uint32_t timeout_ms)
  708. {
  709. if (BL_SendCMDSetAddress()) {
  710. if (!BL_SendCMDSetBuffer(buf, nbytes)) {
  711. blheli.ack = ACK_D_GENERAL_ERROR;
  712. return false;
  713. }
  714. uint8_t sCMD[] = {cmd, 0x01};
  715. if (!BL_SendBuf(sCMD, 2)) {
  716. return false;
  717. }
  718. return (BL_GetACK(timeout_ms) == brSUCCESS);
  719. }
  720. blheli.ack = ACK_D_GENERAL_ERROR;
  721. return false;
  722. }
  723. uint8_t AP_BLHeli::BL_WriteFlash(const uint8_t *buf, uint16_t n)
  724. {
  725. return BL_WriteA(CMD_PROG_FLASH, buf, n, 250);
  726. }
  727. bool AP_BLHeli::BL_VerifyFlash(const uint8_t *buf, uint16_t n)
  728. {
  729. if (BL_SendCMDSetAddress()) {
  730. if (!BL_SendCMDSetBuffer(buf, n)) {
  731. return false;
  732. }
  733. uint8_t sCMD[] = {CMD_VERIFY_FLASH_ARM, 0x01};
  734. if (!BL_SendBuf(sCMD, 2)) {
  735. return false;
  736. }
  737. uint8_t ack = BL_GetACK(40);
  738. switch (ack) {
  739. case brSUCCESS:
  740. blheli.ack = ACK_OK;
  741. break;
  742. case brERRORVERIFY:
  743. blheli.ack = ACK_I_VERIFY_ERROR;
  744. break;
  745. default:
  746. blheli.ack = ACK_D_GENERAL_ERROR;
  747. break;
  748. }
  749. return true;
  750. }
  751. return false;
  752. }
  753. /*
  754. process a blheli 4way command from GCS
  755. */
  756. void AP_BLHeli::blheli_process_command(void)
  757. {
  758. debug("BLHeli cmd 0x%02x len=%u", blheli.command, blheli.param_len);
  759. blheli.ack = ACK_OK;
  760. switch (blheli.command) {
  761. case cmd_InterfaceTestAlive: {
  762. debug("cmd_InterfaceTestAlive");
  763. BL_SendCMDKeepAlive();
  764. if (blheli.ack != ACK_OK) {
  765. setDisconnected();
  766. }
  767. uint8_t b = 0;
  768. blheli_send_reply(&b, 1);
  769. break;
  770. }
  771. case cmd_ProtocolGetVersion: {
  772. debug("cmd_ProtocolGetVersion");
  773. uint8_t buf[1];
  774. buf[0] = SERIAL_4WAY_PROTOCOL_VER;
  775. blheli_send_reply(buf, sizeof(buf));
  776. break;
  777. }
  778. case cmd_InterfaceGetName: {
  779. debug("cmd_InterfaceGetName");
  780. uint8_t buf[5] = { 4, 'A', 'R', 'D', 'U' };
  781. blheli_send_reply(buf, sizeof(buf));
  782. break;
  783. }
  784. case cmd_InterfaceGetVersion: {
  785. debug("cmd_InterfaceGetVersion");
  786. uint8_t buf[2] = { SERIAL_4WAY_VERSION_HI, SERIAL_4WAY_VERSION_LO };
  787. blheli_send_reply(buf, sizeof(buf));
  788. break;
  789. }
  790. case cmd_InterfaceExit: {
  791. debug("cmd_InterfaceExit");
  792. msp.escMode = PROTOCOL_NONE;
  793. uint8_t b = 0;
  794. blheli_send_reply(&b, 1);
  795. hal.rcout->serial_end();
  796. serial_start_ms = 0;
  797. if (motors_disabled) {
  798. motors_disabled = false;
  799. SRV_Channels::set_disabled_channel_mask(0);
  800. }
  801. if (uart_locked) {
  802. debug("Unlocked UART");
  803. uart->lock_port(0, 0);
  804. uart_locked = false;
  805. }
  806. memset(blheli.connected, 0, sizeof(blheli.connected));
  807. break;
  808. }
  809. case cmd_DeviceReset: {
  810. debug("cmd_DeviceReset(%u)", unsigned(blheli.buf[0]));
  811. if (blheli.buf[0] >= num_motors) {
  812. debug("bad reset channel %u", blheli.buf[0]);
  813. blheli.ack = ACK_D_GENERAL_ERROR;
  814. blheli_send_reply(&blheli.buf[0], 1);
  815. break;
  816. }
  817. blheli.chan = blheli.buf[0];
  818. switch (blheli.interface_mode[blheli.chan]) {
  819. case imSIL_BLB:
  820. case imATM_BLB:
  821. case imARM_BLB:
  822. BL_SendCMDRunRestartBootloader();
  823. break;
  824. case imSK:
  825. break;
  826. }
  827. blheli_send_reply(&blheli.chan, 1);
  828. setDisconnected();
  829. break;
  830. }
  831. case cmd_DeviceInitFlash: {
  832. debug("cmd_DeviceInitFlash(%u)", unsigned(blheli.buf[0]));
  833. if (blheli.buf[0] >= num_motors) {
  834. debug("bad channel %u", blheli.buf[0]);
  835. break;
  836. }
  837. blheli.chan = blheli.buf[0];
  838. blheli.ack = ACK_OK;
  839. BL_ConnectEx();
  840. uint8_t buf[4] = {blheli.deviceInfo[blheli.chan][0],
  841. blheli.deviceInfo[blheli.chan][1],
  842. blheli.deviceInfo[blheli.chan][2],
  843. blheli.deviceInfo[blheli.chan][3]}; // device ID
  844. blheli_send_reply(buf, sizeof(buf));
  845. break;
  846. }
  847. case cmd_InterfaceSetMode: {
  848. debug("cmd_InterfaceSetMode(%u)", unsigned(blheli.buf[0]));
  849. blheli.interface_mode[blheli.chan] = blheli.buf[0];
  850. blheli_send_reply(&blheli.interface_mode[blheli.chan], 1);
  851. break;
  852. }
  853. case cmd_DeviceRead: {
  854. uint16_t nbytes = blheli.buf[0]?blheli.buf[0]:256;
  855. debug("cmd_DeviceRead(%u) n=%u", blheli.chan, nbytes);
  856. uint8_t buf[nbytes];
  857. uint8_t cmd = blheli.interface_mode[blheli.chan]==imATM_BLB?CMD_READ_FLASH_ATM:CMD_READ_FLASH_SIL;
  858. if (!BL_ReadA(cmd, buf, nbytes)) {
  859. nbytes = 1;
  860. }
  861. blheli_send_reply(buf, nbytes);
  862. break;
  863. }
  864. case cmd_DevicePageErase: {
  865. uint8_t page = blheli.buf[0];
  866. debug("cmd_DevicePageErase(%u) im=%u", page, blheli.interface_mode[blheli.chan]);
  867. switch (blheli.interface_mode[blheli.chan]) {
  868. case imSIL_BLB:
  869. case imARM_BLB: {
  870. if (blheli.interface_mode[blheli.chan] == imARM_BLB) {
  871. // Address =Page * 1024
  872. blheli.address = page << 10;
  873. } else {
  874. // Address =Page * 512
  875. blheli.address = page << 9;
  876. }
  877. debug("ARM PageErase 0x%04x", blheli.address);
  878. BL_PageErase();
  879. blheli.address = 0;
  880. blheli_send_reply(&page, 1);
  881. break;
  882. }
  883. default:
  884. blheli.ack = ACK_I_INVALID_CMD;
  885. blheli_send_reply(&page, 1);
  886. break;
  887. }
  888. break;
  889. }
  890. case cmd_DeviceWrite: {
  891. uint16_t nbytes = blheli.param_len;
  892. debug("cmd_DeviceWrite n=%u im=%u", nbytes, blheli.interface_mode[blheli.chan]);
  893. uint8_t buf[nbytes];
  894. memcpy(buf, blheli.buf, nbytes);
  895. switch (blheli.interface_mode[blheli.chan]) {
  896. case imSIL_BLB:
  897. case imATM_BLB:
  898. case imARM_BLB: {
  899. BL_WriteFlash(buf, nbytes);
  900. break;
  901. }
  902. case imSK: {
  903. debug("Unsupported flash mode imSK");
  904. break;
  905. }
  906. }
  907. uint8_t b=0;
  908. blheli_send_reply(&b, 1);
  909. break;
  910. }
  911. case cmd_DeviceVerify: {
  912. uint16_t nbytes = blheli.param_len;
  913. debug("cmd_DeviceWrite n=%u im=%u", nbytes, blheli.interface_mode[blheli.chan]);
  914. switch (blheli.interface_mode[blheli.chan]) {
  915. case imARM_BLB: {
  916. uint8_t buf[nbytes];
  917. memcpy(buf, blheli.buf, nbytes);
  918. BL_VerifyFlash(buf, nbytes);
  919. break;
  920. }
  921. default:
  922. blheli.ack = ACK_I_INVALID_CMD;
  923. break;
  924. }
  925. uint8_t b=0;
  926. blheli_send_reply(&b, 1);
  927. break;
  928. }
  929. case cmd_DeviceReadEEprom: {
  930. uint16_t nbytes = blheli.buf[0]?blheli.buf[0]:256;
  931. uint8_t buf[nbytes];
  932. debug("cmd_DeviceReadEEprom n=%u im=%u", nbytes, blheli.interface_mode[blheli.chan]);
  933. switch (blheli.interface_mode[blheli.chan]) {
  934. case imATM_BLB: {
  935. if (!BL_ReadA(CMD_READ_EEPROM, buf, nbytes)) {
  936. blheli.ack = ACK_D_GENERAL_ERROR;
  937. }
  938. break;
  939. }
  940. default:
  941. blheli.ack = ACK_I_INVALID_CMD;
  942. break;
  943. }
  944. if (blheli.ack != ACK_OK) {
  945. nbytes = 1;
  946. buf[0] = 0;
  947. }
  948. blheli_send_reply(buf, nbytes);
  949. break;
  950. }
  951. case cmd_DeviceWriteEEprom: {
  952. uint16_t nbytes = blheli.param_len;
  953. uint8_t buf[nbytes];
  954. memcpy(buf, blheli.buf, nbytes);
  955. debug("cmd_DeviceWriteEEprom n=%u im=%u", nbytes, blheli.interface_mode[blheli.chan]);
  956. switch (blheli.interface_mode[blheli.chan]) {
  957. case imATM_BLB:
  958. BL_WriteA(CMD_PROG_EEPROM, buf, nbytes, 1000);
  959. break;
  960. default:
  961. blheli.ack = ACK_D_GENERAL_ERROR;
  962. break;
  963. }
  964. uint8_t b = 0;
  965. blheli_send_reply(&b, 1);
  966. break;
  967. }
  968. case cmd_DeviceEraseAll:
  969. case cmd_DeviceC2CK_LOW:
  970. default:
  971. // ack=unknown command
  972. blheli.ack = ACK_I_INVALID_CMD;
  973. debug("Unknown BLHeli protocol 0x%02x", blheli.command);
  974. uint8_t b = 0;
  975. blheli_send_reply(&b, 1);
  976. break;
  977. }
  978. }
  979. /*
  980. process an input byte, return true if we have received a whole
  981. packet with correct CRC
  982. */
  983. bool AP_BLHeli::process_input(uint8_t b)
  984. {
  985. bool valid_packet = false;
  986. if (msp.escMode == PROTOCOL_4WAY && blheli.state == BLHELI_IDLE && b == '$') {
  987. debug("Change to MSP mode");
  988. msp.escMode = PROTOCOL_NONE;
  989. hal.rcout->serial_end();
  990. serial_start_ms = 0;
  991. }
  992. if (msp.escMode != PROTOCOL_4WAY && msp.state == MSP_IDLE && b == '/') {
  993. debug("Change to BLHeli mode");
  994. memset(blheli.connected, 0, sizeof(blheli.connected));
  995. msp.escMode = PROTOCOL_4WAY;
  996. }
  997. if (msp.escMode == PROTOCOL_4WAY) {
  998. blheli_4way_process_byte(b);
  999. } else {
  1000. msp_process_byte(b);
  1001. }
  1002. if (msp.escMode == PROTOCOL_4WAY) {
  1003. if (blheli.state == BLHELI_COMMAND_RECEIVED) {
  1004. valid_packet = true;
  1005. last_valid_ms = AP_HAL::millis();
  1006. if (uart->lock_port(BLHELI_UART_LOCK_KEY, 0)) {
  1007. uart_locked = true;
  1008. }
  1009. blheli_process_command();
  1010. blheli.state = BLHELI_IDLE;
  1011. msp.state = MSP_IDLE;
  1012. }
  1013. } else if (msp.state == MSP_COMMAND_RECEIVED) {
  1014. if (msp.packetType == MSP_PACKET_COMMAND) {
  1015. valid_packet = true;
  1016. if (uart->lock_port(BLHELI_UART_LOCK_KEY, 0)) {
  1017. uart_locked = true;
  1018. }
  1019. last_valid_ms = AP_HAL::millis();
  1020. msp_process_command();
  1021. }
  1022. msp.state = MSP_IDLE;
  1023. blheli.state = BLHELI_IDLE;
  1024. }
  1025. return valid_packet;
  1026. }
  1027. /*
  1028. protocol handler for detecting BLHeli input
  1029. */
  1030. bool AP_BLHeli::protocol_handler(uint8_t b, AP_HAL::UARTDriver *_uart)
  1031. {
  1032. uart = _uart;
  1033. if (hal.util->get_soft_armed()) {
  1034. // don't allow MSP control when armed
  1035. return false;
  1036. }
  1037. return process_input(b);
  1038. }
  1039. /*
  1040. run a connection test to the ESCs. This is used to test the
  1041. operation of the BLHeli ESC protocol
  1042. */
  1043. void AP_BLHeli::run_connection_test(uint8_t chan)
  1044. {
  1045. debug_uart = hal.console;
  1046. uint8_t saved_chan = blheli.chan;
  1047. if (chan >= num_motors) {
  1048. debug("bad channel %u", chan);
  1049. return;
  1050. }
  1051. blheli.chan = chan;
  1052. debug("Running test on channel %u", blheli.chan);
  1053. run_test.set_and_notify(0);
  1054. bool passed = false;
  1055. for (uint8_t tries=0; tries<5; tries++) {
  1056. blheli.ack = ACK_OK;
  1057. setDisconnected();
  1058. if (BL_ConnectEx()) {
  1059. uint8_t buf[256];
  1060. uint8_t cmd = blheli.interface_mode[blheli.chan]==imATM_BLB?CMD_READ_FLASH_ATM:CMD_READ_FLASH_SIL;
  1061. passed = true;
  1062. blheli.address = blheli.interface_mode[blheli.chan]==imATM_BLB?0:0x7c00;
  1063. passed &= BL_ReadA(cmd, buf, sizeof(buf));
  1064. if (blheli.interface_mode[blheli.chan]==imARM_BLB) {
  1065. if (passed) {
  1066. // read status structure
  1067. blheli.address = esc_status_addr;
  1068. passed &= BL_SendCMDSetAddress();
  1069. }
  1070. if (passed) {
  1071. struct esc_status status;
  1072. passed &= BL_ReadA(CMD_READ_FLASH_SIL, (uint8_t *)&status, sizeof(status));
  1073. }
  1074. }
  1075. BL_SendCMDRunRestartBootloader();
  1076. break;
  1077. }
  1078. }
  1079. hal.rcout->serial_end();
  1080. SRV_Channels::set_disabled_channel_mask(0);
  1081. motors_disabled = false;
  1082. serial_start_ms = 0;
  1083. blheli.chan = saved_chan;
  1084. debug("Test %s", passed?"PASSED":"FAILED");
  1085. debug_uart = nullptr;
  1086. }
  1087. /*
  1088. update BLHeli
  1089. Used to install protocol handler
  1090. */
  1091. void AP_BLHeli::update(void)
  1092. {
  1093. if (initialised &&
  1094. timeout_sec &&
  1095. uart_locked &&
  1096. AP_HAL::millis() - last_valid_ms > uint32_t(timeout_sec.get())*1000U) {
  1097. // we're not processing requests any more, shutdown serial
  1098. // output
  1099. if (serial_start_ms) {
  1100. hal.rcout->serial_end();
  1101. serial_start_ms = 0;
  1102. }
  1103. if (motors_disabled) {
  1104. motors_disabled = false;
  1105. SRV_Channels::set_disabled_channel_mask(0);
  1106. }
  1107. debug("Unlocked UART");
  1108. uart->lock_port(0, 0);
  1109. uart_locked = false;
  1110. }
  1111. if (initialised || (channel_mask.get() == 0 && channel_auto.get() == 0)) {
  1112. if (initialised && run_test.get() > 0) {
  1113. run_connection_test(run_test.get() - 1);
  1114. }
  1115. return;
  1116. }
  1117. initialised = true;
  1118. run_test.set_and_notify(0);
  1119. if (last_control_port > 0 && last_control_port != control_port) {
  1120. gcs().install_alternative_protocol((mavlink_channel_t)(MAVLINK_COMM_0+last_control_port), nullptr);
  1121. last_control_port = -1;
  1122. }
  1123. if (gcs().install_alternative_protocol((mavlink_channel_t)(MAVLINK_COMM_0+control_port),
  1124. FUNCTOR_BIND_MEMBER(&AP_BLHeli::protocol_handler,
  1125. bool, uint8_t, AP_HAL::UARTDriver *))) {
  1126. debug("BLHeli installed on port %u", (unsigned)control_port);
  1127. last_control_port = control_port;
  1128. }
  1129. uint16_t mask = uint16_t(channel_mask.get());
  1130. /*
  1131. allow mode override - this makes it possible to use DShot for
  1132. rovers and subs, plus for quadplane fwd motors
  1133. */
  1134. AP_HAL::RCOutput::output_mode mode = AP_HAL::RCOutput::MODE_PWM_NONE;
  1135. switch (AP_Motors::pwm_type(output_type.get())) {
  1136. case AP_Motors::PWM_TYPE_ONESHOT:
  1137. mode = AP_HAL::RCOutput::MODE_PWM_ONESHOT;
  1138. break;
  1139. case AP_Motors::PWM_TYPE_ONESHOT125:
  1140. mode = AP_HAL::RCOutput::MODE_PWM_ONESHOT125;
  1141. break;
  1142. case AP_Motors::PWM_TYPE_BRUSHED:
  1143. mode = AP_HAL::RCOutput::MODE_PWM_BRUSHED;
  1144. break;
  1145. case AP_Motors::PWM_TYPE_DSHOT150:
  1146. mode = AP_HAL::RCOutput::MODE_PWM_DSHOT150;
  1147. break;
  1148. case AP_Motors::PWM_TYPE_DSHOT300:
  1149. mode = AP_HAL::RCOutput::MODE_PWM_DSHOT300;
  1150. break;
  1151. case AP_Motors::PWM_TYPE_DSHOT600:
  1152. mode = AP_HAL::RCOutput::MODE_PWM_DSHOT600;
  1153. break;
  1154. case AP_Motors::PWM_TYPE_DSHOT1200:
  1155. mode = AP_HAL::RCOutput::MODE_PWM_DSHOT1200;
  1156. break;
  1157. default:
  1158. break;
  1159. }
  1160. if (mask && mode != AP_HAL::RCOutput::MODE_PWM_NONE) {
  1161. hal.rcout->set_output_mode(mask, mode);
  1162. }
  1163. #if APM_BUILD_TYPE(APM_BUILD_ArduCopter) || APM_BUILD_TYPE(APM_BUILD_ArduPlane)
  1164. /*
  1165. plane and copter can use AP_Motors to get an automatic mask
  1166. */
  1167. if (channel_auto.get() == 1) {
  1168. AP_Motors *motors = AP_Motors::get_singleton();
  1169. if (motors) {
  1170. mask |= motors->get_motor_mask();
  1171. }
  1172. }
  1173. #endif
  1174. // tell SRV_Channels about ESC capabilities
  1175. SRV_Channels::set_digital_mask(mask);
  1176. SRV_Channels::set_reversible_mask(uint16_t(channel_reversible_mask.get()) & mask);
  1177. hal.rcout->set_reversible_mask(channel_reversible_mask.get() & mask);
  1178. // add motors from channel mask
  1179. for (uint8_t i=0; i<16 && num_motors < max_motors; i++) {
  1180. if (mask & (1U<<i)) {
  1181. motor_map[num_motors] = i;
  1182. num_motors++;
  1183. }
  1184. }
  1185. motor_mask = mask;
  1186. debug("ESC: %u motors mask=0x%04x", num_motors, mask);
  1187. if (num_motors != 0 && telem_rate > 0) {
  1188. AP_SerialManager *serial_manager = AP_SerialManager::get_singleton();
  1189. if (serial_manager) {
  1190. telem_uart = serial_manager->find_serial(AP_SerialManager::SerialProtocol_ESCTelemetry,0);
  1191. }
  1192. }
  1193. }
  1194. // get the most recent telemetry data packet for a motor
  1195. bool AP_BLHeli::get_telem_data(uint8_t esc_index, struct telem_data &td)
  1196. {
  1197. if (esc_index >= max_motors) {
  1198. return false;
  1199. }
  1200. if (last_telem[esc_index].timestamp_ms == 0) {
  1201. return false;
  1202. }
  1203. td = last_telem[esc_index];
  1204. return true;
  1205. }
  1206. /*
  1207. implement the 8 bit CRC used by the BLHeli ESC telemetry protocol
  1208. */
  1209. uint8_t AP_BLHeli::telem_crc8(uint8_t crc, uint8_t crc_seed) const
  1210. {
  1211. uint8_t crc_u = crc;
  1212. crc_u ^= crc_seed;
  1213. for (uint8_t i=0; i<8; i++) {
  1214. crc_u = ( crc_u & 0x80 ) ? 0x7 ^ ( crc_u << 1 ) : ( crc_u << 1 );
  1215. }
  1216. return crc_u;
  1217. }
  1218. /*
  1219. read an ESC telemetry packet
  1220. */
  1221. void AP_BLHeli::read_telemetry_packet(void)
  1222. {
  1223. uint8_t buf[telem_packet_size];
  1224. uint8_t crc = 0;
  1225. for (uint8_t i=0; i<telem_packet_size; i++) {
  1226. int16_t v = telem_uart->read();
  1227. if (v < 0) {
  1228. // short read, we should have 10 bytes ready when this function is called
  1229. return;
  1230. }
  1231. buf[i] = uint8_t(v);
  1232. }
  1233. // calculate crc
  1234. for (uint8_t i=0; i<telem_packet_size-1; i++) {
  1235. crc = telem_crc8(buf[i], crc);
  1236. }
  1237. if (buf[telem_packet_size-1] != crc) {
  1238. // bad crc
  1239. debug("Bad CRC on %u\n", last_telem_esc);
  1240. return;
  1241. }
  1242. struct telem_data td;
  1243. td.temperature = buf[0];
  1244. td.voltage = (buf[1]<<8) | buf[2];
  1245. td.current = (buf[3]<<8) | buf[4];
  1246. td.consumption = (buf[5]<<8) | buf[6];
  1247. td.rpm = ((buf[7]<<8) | buf[8]) * motor_poles;
  1248. td.timestamp_ms = AP_HAL::millis();
  1249. last_telem[last_telem_esc] = td;
  1250. last_telem[last_telem_esc].count++;
  1251. AP_Logger *logger = AP_Logger::get_singleton();
  1252. if (logger && logger->logging_enabled()) {
  1253. logger->Write_ESC(uint8_t(last_telem_esc),
  1254. AP_HAL::micros64(),
  1255. td.rpm*100U,
  1256. td.voltage,
  1257. td.current,
  1258. td.temperature * 100U,
  1259. td.consumption);
  1260. }
  1261. if (debug_level >= 2) {
  1262. hal.console->printf("ESC[%u] T=%u V=%u C=%u con=%u RPM=%u t=%u\n",
  1263. last_telem_esc,
  1264. td.temperature,
  1265. td.voltage,
  1266. td.current,
  1267. td.consumption,
  1268. td.rpm, (unsigned)AP_HAL::millis());
  1269. }
  1270. }
  1271. /*
  1272. update BLHeli telemetry handling
  1273. This is called on push() in SRV_Channels
  1274. */
  1275. void AP_BLHeli::update_telemetry(void)
  1276. {
  1277. if (!telem_uart) {
  1278. return;
  1279. }
  1280. uint32_t now = AP_HAL::micros();
  1281. uint32_t telem_rate_us = 1000000U / uint32_t(telem_rate.get() * num_motors);
  1282. if (telem_rate_us < 2000) {
  1283. // make sure we have a gap between frames
  1284. telem_rate_us = 2000;
  1285. }
  1286. if (!telem_uart_started) {
  1287. // we need to use begin() here to ensure the correct thread owns the uart
  1288. telem_uart->begin(115200);
  1289. telem_uart_started = true;
  1290. }
  1291. uint32_t nbytes = telem_uart->available();
  1292. if (nbytes > telem_packet_size) {
  1293. // if we have more than 10 bytes then we don't know which ESC
  1294. // they are from. Throw them all away
  1295. while (nbytes--) {
  1296. telem_uart->read();
  1297. }
  1298. return;
  1299. }
  1300. if (nbytes > 0 &&
  1301. nbytes < telem_packet_size &&
  1302. (last_telem_byte_read_us == 0 ||
  1303. now - last_telem_byte_read_us < 1000)) {
  1304. // wait a bit longer, we don't have enough bytes yet
  1305. if (last_telem_byte_read_us == 0) {
  1306. last_telem_byte_read_us = now;
  1307. }
  1308. return;
  1309. }
  1310. if (nbytes > 0 && nbytes < telem_packet_size) {
  1311. // we've waited long enough, discard bytes if we don't have 10 yet
  1312. while (nbytes--) {
  1313. telem_uart->read();
  1314. }
  1315. return;
  1316. }
  1317. if (nbytes == telem_packet_size) {
  1318. // we have a full packet ready to parse
  1319. read_telemetry_packet();
  1320. last_telem_byte_read_us = 0;
  1321. }
  1322. if (now - last_telem_request_us >= telem_rate_us) {
  1323. // ask the next ESC for telemetry
  1324. last_telem_esc = (last_telem_esc + 1) % num_motors;
  1325. uint16_t mask = 1U << motor_map[last_telem_esc];
  1326. hal.rcout->set_telem_request_mask(mask);
  1327. last_telem_request_us = now;
  1328. }
  1329. }
  1330. /*
  1331. send ESC telemetry messages over MAVLink
  1332. */
  1333. void AP_BLHeli::send_esc_telemetry_mavlink(uint8_t mav_chan)
  1334. {
  1335. if (num_motors == 0) {
  1336. return;
  1337. }
  1338. uint8_t temperature[4] {};
  1339. uint16_t voltage[4] {};
  1340. uint16_t current[4] {};
  1341. uint16_t totalcurrent[4] {};
  1342. uint16_t rpm[4] {};
  1343. uint16_t count[4] {};
  1344. uint32_t now = AP_HAL::millis();
  1345. for (uint8_t i=0; i<num_motors; i++) {
  1346. uint8_t idx = i % 4;
  1347. if (last_telem[i].timestamp_ms && (now - last_telem[i].timestamp_ms < 1000)) {
  1348. temperature[idx] = last_telem[i].temperature;
  1349. voltage[idx] = last_telem[i].voltage;
  1350. current[idx] = last_telem[i].current;
  1351. totalcurrent[idx] = last_telem[i].consumption;
  1352. rpm[idx] = last_telem[i].rpm;
  1353. count[idx] = last_telem[i].count;
  1354. } else {
  1355. temperature[idx] = 0;
  1356. voltage[idx] = 0;
  1357. current[idx] = 0;
  1358. totalcurrent[idx] = 0;
  1359. rpm[idx] = 0;
  1360. count[idx] = 0;
  1361. }
  1362. if (i % 4 == 3 || i == num_motors - 1) {
  1363. if (!HAVE_PAYLOAD_SPACE((mavlink_channel_t)mav_chan, ESC_TELEMETRY_1_TO_4)) {
  1364. return;
  1365. }
  1366. if (i < 4) {
  1367. mavlink_msg_esc_telemetry_1_to_4_send((mavlink_channel_t)mav_chan, temperature, voltage, current, totalcurrent, rpm, count);
  1368. } else {
  1369. mavlink_msg_esc_telemetry_5_to_8_send((mavlink_channel_t)mav_chan, temperature, voltage, current, totalcurrent, rpm, count);
  1370. }
  1371. }
  1372. }
  1373. }
  1374. #endif // HAVE_AP_BLHELI_SUPPORT