RCOutput_Tap.cpp 17 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580
  1. /*
  2. * Copyright (c) 2016 PX4 Development Team. All rights reserved.
  3. * Copyright (C) 2017 Intel Corporation. All rights reserved.
  4. *
  5. * This file is free software: you can redistribute it and/or modify it
  6. * under the terms of the GNU General Public License as published by the
  7. * Free Software Foundation, either version 3 of the License, or
  8. * (at your option) any later version.
  9. *
  10. * This file is distributed in the hope that it will be useful, but
  11. * WITHOUT ANY WARRANTY; without even the implied warranty of
  12. * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
  13. * See the GNU General Public License for more details.
  14. *
  15. * You should have received a copy of the GNU General Public License along
  16. * with this program. If not, see <http://www.gnu.org/licenses/>.
  17. */
  18. /*
  19. * Implementation of TAP UART ESCs. Used the implementation from PX4 as a base
  20. * which is BSD-licensed:
  21. *
  22. * Redistribution and use in source and binary forms, with or without
  23. * modification, are permitted provided that the following conditions
  24. * are met:
  25. *
  26. * 1. Redistributions of source code must retain the above copyright
  27. * notice, this list of conditions and the following disclaimer.
  28. * 2. Redistributions in binary form must reproduce the above copyright
  29. * notice, this list of conditions and the following disclaimer in
  30. * the documentation and/or other materials provided with the
  31. * distribution.
  32. * 3. Neither the name PX4 nor the names of its contributors may be
  33. * used to endorse or promote products derived from this software
  34. * without specific prior written permission.
  35. *
  36. * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
  37. * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
  38. * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
  39. * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
  40. * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
  41. * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
  42. * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
  43. * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
  44. * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
  45. * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
  46. * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
  47. * POSSIBILITY OF SUCH DAMAGE.
  48. */
  49. #include <AP_HAL/AP_HAL.h>
  50. #ifdef HAL_RCOUTPUT_TAP_DEVICE
  51. #include "RCOutput_Tap.h"
  52. #include <errno.h>
  53. #include <fcntl.h>
  54. #include <stdio.h>
  55. #include <sys/stat.h>
  56. #include <sys/types.h>
  57. #include <termios.h>
  58. #include <unistd.h>
  59. #include <AP_Math/AP_Math.h>
  60. #define DEBUG 0
  61. #if DEBUG
  62. #define debug(fmt, args...) ::printf(fmt "\n", ##args)
  63. #else
  64. #define debug(fmt, args...)
  65. #endif
  66. extern const AP_HAL::HAL &hal;
  67. /****** ESC data types ******/
  68. #define ESC_HAVE_CURRENT_SENSOR
  69. static const uint8_t crcTable[256] = {
  70. 0x00, 0xE7, 0x29, 0xCE, 0x52, 0xB5, 0x7B, 0x9C, 0xA4, 0x43, 0x8D, 0x6A,
  71. 0xF6, 0x11, 0xDF, 0x38, 0xAF, 0x48, 0x86, 0x61, 0xFD, 0x1A, 0xD4, 0x33,
  72. 0x0B, 0xEC, 0x22, 0xC5, 0x59, 0xBE, 0x70, 0x97, 0xB9, 0x5E, 0x90, 0x77,
  73. 0xEB, 0x0C, 0xC2, 0x25, 0x1D, 0xFA, 0x34, 0xD3, 0x4F, 0xA8, 0x66, 0x81,
  74. 0x16, 0xF1, 0x3F, 0xD8, 0x44, 0xA3, 0x6D, 0x8A, 0xB2, 0x55, 0x9B, 0x7C,
  75. 0xE0, 0x07, 0xC9, 0x2E, 0x95, 0x72, 0xBC, 0x5B, 0xC7, 0x20, 0xEE, 0x09,
  76. 0x31, 0xD6, 0x18, 0xFF, 0x63, 0x84, 0x4A, 0xAD, 0x3A, 0xDD, 0x13, 0xF4,
  77. 0x68, 0x8F, 0x41, 0xA6, 0x9E, 0x79, 0xB7, 0x50, 0xCC, 0x2B, 0xE5, 0x02,
  78. 0x2C, 0xCB, 0x05, 0xE2, 0x7E, 0x99, 0x57, 0xB0, 0x88, 0x6F, 0xA1, 0x46,
  79. 0xDA, 0x3D, 0xF3, 0x14, 0x83, 0x64, 0xAA, 0x4D, 0xD1, 0x36, 0xF8, 0x1F,
  80. 0x27, 0xC0, 0x0E, 0xE9, 0x75, 0x92, 0x5C, 0xBB, 0xCD, 0x2A, 0xE4, 0x03,
  81. 0x9F, 0x78, 0xB6, 0x51, 0x69, 0x8E, 0x40, 0xA7, 0x3B, 0xDC, 0x12, 0xF5,
  82. 0x62, 0x85, 0x4B, 0xAC, 0x30, 0xD7, 0x19, 0xFE, 0xC6, 0x21, 0xEF, 0x08,
  83. 0x94, 0x73, 0xBD, 0x5A, 0x74, 0x93, 0x5D, 0xBA, 0x26, 0xC1, 0x0F, 0xE8,
  84. 0xD0, 0x37, 0xF9, 0x1E, 0x82, 0x65, 0xAB, 0x4C, 0xDB, 0x3C, 0xF2, 0x15,
  85. 0x89, 0x6E, 0xA0, 0x47, 0x7F, 0x98, 0x56, 0xB1, 0x2D, 0xCA, 0x04, 0xE3,
  86. 0x58, 0xBF, 0x71, 0x96, 0x0A, 0xED, 0x23, 0xC4, 0xFC, 0x1B, 0xD5, 0x32,
  87. 0xAE, 0x49, 0x87, 0x60, 0xF7, 0x10, 0xDE, 0x39, 0xA5, 0x42, 0x8C, 0x6B,
  88. 0x53, 0xB4, 0x7A, 0x9D, 0x01, 0xE6, 0x28, 0xCF, 0xE1, 0x06, 0xC8, 0x2F,
  89. 0xB3, 0x54, 0x9A, 0x7D, 0x45, 0xA2, 0x6C, 0x8B, 0x17, 0xF0, 0x3E, 0xD9,
  90. 0x4E, 0xA9, 0x67, 0x80, 0x1C, 0xFB, 0x35, 0xD2, 0xEA, 0x0D, 0xC3, 0x24,
  91. 0xB8, 0x5F, 0x91, 0x76
  92. };
  93. // Circular from back right in CCW direction
  94. static const uint8_t device_mux_map[] = {0, 1, 4, 3, 2, 5, 7, 8};
  95. // 0 is CW, 1 is CCW
  96. static const uint8_t device_dir_map[] = {0, 1, 0, 1, 0, 1, 0, 1};
  97. #define TAP_ESC_MAX_PACKET_LEN 20
  98. #define TAP_ESC_MAX_MOTOR_NUM 8
  99. /*
  100. * ESC_POS maps the values stored in the channelMapTable to reorder the ESC's
  101. * id so that that match the mux setting, so that the ressonder's data
  102. * will be read.
  103. * The index on channelMapTable[p] p is the physical ESC
  104. * The value it is set to is the logical value from ESC_POS[p]
  105. * Phy Log
  106. * 0 0
  107. * 1 1
  108. * 2 4
  109. * 3 3
  110. * 4 2
  111. * 5 5
  112. * ....
  113. *
  114. */
  115. #define RPMMAX 1900
  116. #define RPMMIN 1200
  117. #define RPMSTOPPED (RPMMIN - 10)
  118. #define MIN_BOOT_TIME_MSEC (550) // Minimum time to wait after Power on before sending commands
  119. namespace ap {
  120. /****** Run ***********/
  121. #define RUN_CHANNEL_VALUE_MASK (uint16_t)0x07ff
  122. #define RUN_RED_LED_ON_MASK (uint16_t)0x0800
  123. #define RUN_GREEN_LED_ON_MASK (uint16_t)0x1000
  124. #define RUN_BLUE_LED_ON_MASK (uint16_t)0x2000
  125. #define RUN_LED_ON_MASK (uint16_t)0x3800
  126. #define RUN_FEEDBACK_ENABLE_MASK (uint16_t)0x4000
  127. #define RUN_REVERSE_MASK (uint16_t)0x8000
  128. struct PACKED RunReq {
  129. uint16_t value[TAP_ESC_MAX_MOTOR_NUM];
  130. };
  131. struct PACKED RunInfoRepsonse {
  132. uint8_t channelID;
  133. uint8_t ESCStatus;
  134. int16_t speed; // -32767 - 32768
  135. #if defined(ESC_HAVE_VOLTAGE_SENSOR)
  136. uint16_t voltage; // 0.00 - 100.00 V
  137. #endif
  138. #if defined(ESC_HAVE_CURRENT_SENSOR)
  139. uint16_t current; // 0.0 - 200.0 A
  140. #endif
  141. #if defined(ESC_HAVE_TEMPERATURE_SENSOR)
  142. uint8_t temperature; // 0 - 256 degree celsius
  143. #endif
  144. };
  145. /****** Run ***********/
  146. /****** ConFigInfoBasic ***********/
  147. struct PACKED ConfigInfoBasicRequest {
  148. uint8_t maxChannelInUse;
  149. uint8_t channelMapTable[TAP_ESC_MAX_MOTOR_NUM];
  150. uint8_t monitorMsgType;
  151. uint8_t controlMode;
  152. uint16_t minChannelValue;
  153. uint16_t maxChannelValue;
  154. };
  155. struct PACKED ConfigInfoBasicResponse {
  156. uint8_t channelID;
  157. ConfigInfoBasicRequest resp;
  158. };
  159. #define ESC_CHANNEL_MAP_CHANNEL 0x0f
  160. #define ESC_CHANNEL_MAP_RUNNING_DIRECTION 0xf0
  161. /****** ConFigInfoBasicResponse ***********/
  162. /****** InfoRequest ***********/
  163. enum InfoTypes {
  164. REQUEST_INFO_BASIC = 0,
  165. REQUEST_INFO_FUll,
  166. REQUEST_INFO_RUN,
  167. REQUEST_INFO_STUDY,
  168. REQUEST_INFO_COMM,
  169. REQUEST_INFO_DEVICE,
  170. };
  171. struct PACKED InfoRequest {
  172. uint8_t channelID;
  173. uint8_t requestInfoType;
  174. };
  175. /****** InfoRequest ***********/
  176. struct PACKED EscPacket {
  177. uint8_t head;
  178. uint8_t len;
  179. uint8_t msg_id;
  180. union {
  181. InfoRequest reqInfo;
  182. ConfigInfoBasicRequest reqConfigInfoBasic;
  183. RunReq reqRun;
  184. ConfigInfoBasicResponse rspConfigInfoBasic;
  185. RunInfoRepsonse rspRunInfo;
  186. uint8_t bytes[100];
  187. } d;
  188. uint8_t crc_data;
  189. };
  190. //static const unsigned ESC_PACKET_DATA_OFFSET = offsetof(EscPacket, d);
  191. static const unsigned ESC_PACKET_DATA_OFFSET = 3;
  192. /******************************************************************************************
  193. * ESCBUS_MSG_ID_RUN_INFO packet
  194. *
  195. * Monitor message of ESCs while motor is running
  196. *
  197. * channelID: assigned channel number
  198. *
  199. * ESCStatus: status of ESC
  200. * Num Health status
  201. * 0 HEALTHY
  202. * 1 WARNING_LOW_VOLTAGE
  203. * 2 WARNING_OVER_CURRENT
  204. * 3 WARNING_OVER_HEAT
  205. * 4 ERROR_MOTOR_LOW_SPEED_LOSE_STEP
  206. * 5 ERROR_MOTOR_STALL
  207. * 6 ERROR_HARDWARE
  208. * 7 ERROR_LOSE_PROPELLER
  209. * 8 ERROR_OVER_CURRENT
  210. *
  211. * speed: -32767 - 32767 rpm
  212. *
  213. * temperature: 0 - 256 celsius degree (if available)
  214. * voltage: 0.00 - 100.00 V (if available)
  215. * current: 0.0 - 200.0 A (if available)
  216. */
  217. enum ESCBUS_ENUM_ESC_STATUS {
  218. ESC_STATUS_HEALTHY,
  219. ESC_STATUS_WARNING_LOW_VOLTAGE,
  220. ESC_STATUS_WARNING_OVER_HEAT,
  221. ESC_STATUS_ERROR_MOTOR_LOW_SPEED_LOSE_STEP,
  222. ESC_STATUS_ERROR_MOTOR_STALL,
  223. ESC_STATUS_ERROR_HARDWARE,
  224. ESC_STATUS_ERROR_LOSE_PROPELLER,
  225. ESC_STATUS_ERROR_OVER_CURRENT,
  226. ESC_STATUS_ERROR_MOTOR_HIGH_SPEED_LOSE_STEP,
  227. ESC_STATUS_ERROR_LOSE_CMD,
  228. };
  229. enum ESCBUS_ENUM_MESSAGE_ID {
  230. // messages or command to ESC
  231. ESCBUS_MSG_ID_CONFIG_BASIC = 0,
  232. ESCBUS_MSG_ID_CONFIG_FULL,
  233. ESCBUS_MSG_ID_RUN,
  234. ESCBUS_MSG_ID_TUNE,
  235. ESCBUS_MSG_ID_DO_CMD,
  236. // messages from ESC
  237. ESCBUS_MSG_ID_REQUEST_INFO,
  238. ESCBUS_MSG_ID_CONFIG_INFO_BASIC, // simple configuration info for request from flight controller
  239. ESCBUS_MSG_ID_CONFIG_INFO_FULL, // full configuration info for request from host such as computer
  240. ESCBUS_MSG_ID_RUN_INFO, // feedback message in RUN mode
  241. ESCBUS_MSG_ID_STUDY_INFO, // studied parameters in STUDY mode
  242. ESCBUS_MSG_ID_COMM_INFO, // communication method info
  243. ESCBUS_MSG_ID_DEVICE_INFO, // ESC device info
  244. ESCBUS_MSG_ID_ASSIGNED_ID, // never touch ESCBUS_MSG_ID_MAX_NUM
  245. //boot loader used
  246. PROTO_OK = 0x10, // INSYNC/OK - 'ok' response
  247. PROTO_FAILED = 0x11, // INSYNC/FAILED - 'fail' response
  248. ESCBUS_MSG_ID_BOOT_SYNC = 0x21, // boot loader used
  249. PROTO_GET_DEVICE = 0x22, // get device ID bytes
  250. PROTO_CHIP_ERASE = 0x23, // erase program area and reset program address
  251. PROTO_PROG_MULTI = 0x27, // write bytes at program address and increment
  252. PROTO_GET_CRC = 0x29, // compute & return a CRC
  253. PROTO_BOOT = 0x30, // boot the application
  254. PROTO_GET_SOFTWARE_VERSION = 0x40,
  255. ESCBUS_MSG_ID_MAX_NUM,
  256. };
  257. enum PARSR_ESC_STATE {
  258. HEAD,
  259. LEN,
  260. ID,
  261. DATA,
  262. CRC,
  263. };
  264. /****************************/
  265. }
  266. using namespace ap;
  267. void RCOutput_Tap::_uart_close()
  268. {
  269. if (_uart_fd < 0) {
  270. return;
  271. }
  272. ::close(_uart_fd);
  273. _uart_fd = -1;
  274. }
  275. bool RCOutput_Tap::_uart_open()
  276. {
  277. // open uart
  278. _uart_fd = open(HAL_RCOUTPUT_TAP_DEVICE, O_RDWR | O_NOCTTY | O_NONBLOCK);
  279. int termios_state = -1;
  280. if (_uart_fd < 0) {
  281. ::fprintf(stderr, "failed to open uart device! %s\n", HAL_RCOUTPUT_TAP_DEVICE);
  282. return -1;
  283. }
  284. struct termios uart_config;
  285. memset(&uart_config, 0, sizeof(uart_config));
  286. tcgetattr(_uart_fd, &uart_config);
  287. // clear ONLCR flag (which appends a CR for every LF)
  288. uart_config.c_oflag &= ~ONLCR;
  289. if ((termios_state = tcsetattr(_uart_fd, TCSANOW, &uart_config)) < 0) {
  290. ::fprintf(stderr, "tcsetattr failed for %s\n", HAL_RCOUTPUT_TAP_DEVICE);
  291. _uart_close();
  292. return false;
  293. }
  294. if (!_uart_set_speed(250000)) {
  295. ::fprintf(stderr, "failed to set baudrate for %s: %m\n",
  296. HAL_RCOUTPUT_TAP_DEVICE);
  297. _uart_close();
  298. return false;
  299. }
  300. return true;
  301. }
  302. void RCOutput_Tap::init()
  303. {
  304. _perf_rcout = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "APM_rcout");
  305. if (!_uart_open()) {
  306. AP_HAL::panic("Unable to open " HAL_RCOUTPUT_TAP_DEVICE);
  307. return;
  308. }
  309. uint32_t now = AP_HAL::millis();
  310. if (now < MIN_BOOT_TIME_MSEC) {
  311. hal.scheduler->delay(MIN_BOOT_TIME_MSEC - now);
  312. }
  313. /* Issue Basic Config */
  314. EscPacket packet = {0xfe, sizeof(ConfigInfoBasicRequest), ESCBUS_MSG_ID_CONFIG_BASIC};
  315. ConfigInfoBasicRequest &config = packet.d.reqConfigInfoBasic;
  316. memset(&config, 0, sizeof(ConfigInfoBasicRequest));
  317. config.maxChannelInUse = _channels_count;
  318. config.controlMode = 1;
  319. /* Assign the id's to the ESCs to match the mux */
  320. for (uint8_t phy_chan_index = 0; phy_chan_index < _channels_count; phy_chan_index++) {
  321. config.channelMapTable[phy_chan_index] = device_mux_map[phy_chan_index] & ESC_CHANNEL_MAP_CHANNEL;
  322. config.channelMapTable[phy_chan_index] |= (device_dir_map[phy_chan_index] << 4) & ESC_CHANNEL_MAP_RUNNING_DIRECTION;
  323. }
  324. config.maxChannelValue = RPMMAX;
  325. config.minChannelValue = RPMMIN;
  326. int ret = _send_packet(packet);
  327. if (ret < 0) {
  328. _uart_close();
  329. AP_HAL::panic("Unable to send configuration to " HAL_RCOUTPUT_TAP_DEVICE);
  330. return;
  331. }
  332. /*
  333. * To Unlock the ESC from the Power up state we need to issue 10
  334. * ESCBUS_MSG_ID_RUN request with all the values 0;
  335. */
  336. EscPacket unlock_packet = {0xfe, _channels_count, ESCBUS_MSG_ID_RUN};
  337. unlock_packet.len *= sizeof(unlock_packet.d.reqRun.value[0]);
  338. memset(unlock_packet.d.bytes, 0, sizeof(packet.d.bytes));
  339. for (uint8_t i = 0; i < 10; i++) {
  340. _send_packet(unlock_packet);
  341. /* Min Packet to Packet time is 1 Ms so use 2 */
  342. hal.scheduler->delay(2);
  343. }
  344. }
  345. int RCOutput_Tap::_send_packet(EscPacket &packet)
  346. {
  347. int packet_len = _crc_packet(packet);
  348. int ret = ::write(_uart_fd, &packet.head, packet_len);
  349. if (ret != packet_len) {
  350. debug("TX ERROR: ret: %d, errno: %d", ret, errno);
  351. }
  352. return ret;
  353. }
  354. uint8_t RCOutput_Tap::_crc8_esc(uint8_t *p, uint8_t len)
  355. {
  356. uint8_t crc = 0;
  357. for (uint8_t i = 0; i < len; i++) {
  358. crc = crcTable[crc ^ *p++];
  359. }
  360. return crc;
  361. }
  362. uint8_t RCOutput_Tap::_crc_packet(EscPacket &p)
  363. {
  364. /* Calculate the crc over Len,ID,data */
  365. p.d.bytes[p.len] = _crc8_esc(&p.len, p.len + 2);
  366. return p.len + ESC_PACKET_DATA_OFFSET + 1;
  367. }
  368. /*
  369. set output frequency
  370. */
  371. void RCOutput_Tap::set_freq(uint32_t chmask, uint16_t freq_hz)
  372. {
  373. }
  374. uint16_t RCOutput_Tap::get_freq(uint8_t ch)
  375. {
  376. return 400;
  377. }
  378. void RCOutput_Tap::enable_ch(uint8_t ch)
  379. {
  380. if (ch >= MAX_MOTORS) {
  381. return;
  382. }
  383. _enabled_channels |= (1U << ch);
  384. }
  385. void RCOutput_Tap::disable_ch(uint8_t ch)
  386. {
  387. if (ch >= MAX_MOTORS) {
  388. return;
  389. }
  390. _enabled_channels &= ~(1U << ch);
  391. }
  392. void RCOutput_Tap::write(uint8_t ch, uint16_t period_us)
  393. {
  394. if (ch >= MAX_MOTORS) {
  395. return;
  396. }
  397. if (!(_enabled_channels & (1U << ch))) {
  398. // not enabled
  399. return;
  400. }
  401. _period[ch] = period_us;
  402. if (!_corking) {
  403. push();
  404. }
  405. }
  406. uint16_t RCOutput_Tap::read(uint8_t ch)
  407. {
  408. if (ch >= MAX_MOTORS) {
  409. return 0;
  410. }
  411. return _period[ch];
  412. }
  413. void RCOutput_Tap::read(uint16_t *period_us, uint8_t len)
  414. {
  415. for (uint8_t i = 0; i < len; i++) {
  416. period_us[i] = read(i);
  417. }
  418. }
  419. void RCOutput_Tap::cork()
  420. {
  421. _corking = true;
  422. }
  423. void RCOutput_Tap::push()
  424. {
  425. _corking = false;
  426. hal.util->perf_begin(_perf_rcout);
  427. uint16_t out[TAP_ESC_MAX_MOTOR_NUM];
  428. uint8_t motor_cnt = _channels_count;
  429. uint8_t motor_mapping[] = {
  430. [0] = 2,
  431. [1] = 1,
  432. [2] = 0,
  433. [3] = 3,
  434. };
  435. // map from the RPM range to 0 - 100% duty cycle for the ESCs
  436. for (uint8_t i = 0; i < motor_cnt; i++) {
  437. uint16_t *val = &out[motor_mapping[i]];
  438. if (!(_enabled_channels & (1U << i))) {
  439. *val = RPMSTOPPED;
  440. } else if (_period[i] < _esc_pwm_min) {
  441. *val = RPMSTOPPED;
  442. } else if (_period[i] >= _esc_pwm_max) {
  443. *val = RPMMAX;
  444. } else {
  445. float period_us = constrain_int16(_period[i], _esc_pwm_min, _esc_pwm_max);
  446. /*
  447. * Map to [ RPMSTOPPED, RPMMAX ] range rather than
  448. * [ RPMMIN, RPMMAX ] because AP_Motors will send us _esc_pwm_min
  449. * when it's disarmed
  450. */
  451. float rpm = (period_us - _esc_pwm_min)/(_esc_pwm_max - _esc_pwm_min)
  452. * (RPMMAX - RPMSTOPPED) + RPMSTOPPED;
  453. *val = (uint16_t) rpm;
  454. }
  455. }
  456. for (uint8_t i = motor_cnt; i < TAP_ESC_MAX_MOTOR_NUM; i++) {
  457. out[i] = RPMSTOPPED;
  458. }
  459. /*
  460. * Value packet format, little endian
  461. *
  462. * | 15 | 14 | 13 | 12 | 11 | 10 ...... 0 |
  463. * ------------------------------------------
  464. * | REV | FEN | BL | GL | RL | RPM value |
  465. *
  466. * RPM value: [ RPMMIN, RPMMAX ]
  467. * RL: LED1
  468. * GL: LED2 (ESC may have only one LED that works, independent of the color)
  469. * BL: LED3
  470. * FEN: Feedback enable
  471. * REV: Reverse direction
  472. */
  473. EscPacket packet = {0xfe, _channels_count, ESCBUS_MSG_ID_RUN};
  474. packet.len *= sizeof(packet.d.reqRun.value[0]);
  475. uint32_t tnow = AP_HAL::millis();
  476. if (tnow - _last_led_update_msec > 250) {
  477. _led_on = !_led_on;
  478. _last_led_update_msec = tnow;
  479. }
  480. for (uint8_t i = 0; i < _channels_count; i++) {
  481. packet.d.reqRun.value[i] = out[i] & RUN_CHANNEL_VALUE_MASK;
  482. if (_led_on) {
  483. packet.d.reqRun.value[i] |= RUN_LED_ON_MASK;
  484. }
  485. }
  486. int ret = _send_packet(packet);
  487. if (ret < 1) {
  488. debug("TX ERROR: ret: %d, errno: %d", ret, errno);
  489. }
  490. hal.util->perf_end(_perf_rcout);
  491. }
  492. #endif