AP_KDECAN.cpp 29 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750
  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. * AP_KDECAN.cpp
  15. *
  16. * Author: Francisco Ferreira
  17. */
  18. #include <AP_HAL/AP_HAL.h>
  19. #if HAL_WITH_UAVCAN
  20. #include <AP_BoardConfig/AP_BoardConfig.h>
  21. #include <AP_BoardConfig/AP_BoardConfig_CAN.h>
  22. #include <AP_Common/AP_Common.h>
  23. #include <AP_HAL/utility/sparse-endian.h>
  24. #include <SRV_Channel/SRV_Channel.h>
  25. #include <GCS_MAVLink/GCS.h>
  26. #include <AP_Scheduler/AP_Scheduler.h>
  27. #include <AP_Math/AP_Math.h>
  28. #include <AP_Motors/AP_Motors.h>
  29. #include <AP_Logger/AP_Logger.h>
  30. #include "AP_KDECAN.h"
  31. extern const AP_HAL::HAL& hal;
  32. #define debug_can(level_debug, fmt, args...) do { if ((level_debug) <= AP::can().get_debug_level_driver(_driver_index)) { printf(fmt, ##args); }} while (0)
  33. #define DEFAULT_NUM_POLES 14
  34. // table of user settable CAN bus parameters
  35. const AP_Param::GroupInfo AP_KDECAN::var_info[] = {
  36. // @Param: NPOLE
  37. // @DisplayName: Number of motor poles
  38. // @Description: Sets the number of motor poles to calculate the correct RPM value
  39. AP_GROUPINFO("NPOLE", 1, AP_KDECAN, _num_poles, DEFAULT_NUM_POLES),
  40. AP_GROUPEND
  41. };
  42. AP_KDECAN::AP_KDECAN()
  43. {
  44. AP_Param::setup_object_defaults(this, var_info);
  45. debug_can(2, "KDECAN: constructed\n\r");
  46. }
  47. AP_KDECAN *AP_KDECAN::get_kdecan(uint8_t driver_index)
  48. {
  49. if (driver_index >= AP::can().get_num_drivers() ||
  50. AP::can().get_protocol_type(driver_index) != AP_BoardConfig_CAN::Protocol_Type_KDECAN) {
  51. return nullptr;
  52. }
  53. return static_cast<AP_KDECAN*>(AP::can().get_driver(driver_index));
  54. }
  55. void AP_KDECAN::init(uint8_t driver_index, bool enable_filters)
  56. {
  57. _driver_index = driver_index;
  58. debug_can(2, "KDECAN: starting init\n\r");
  59. if (_initialized) {
  60. debug_can(1, "KDECAN: already initialized\n\r");
  61. return;
  62. }
  63. // get CAN manager instance
  64. AP_HAL::CANManager* can_mgr = hal.can_mgr[driver_index];
  65. if (can_mgr == nullptr) {
  66. debug_can(1, "KDECAN: no mgr for this driver\n\r");
  67. return;
  68. }
  69. if (!can_mgr->is_initialized()) {
  70. debug_can(1, "KDECAN: mgr not initialized\n\r");
  71. return;
  72. }
  73. // store pointer to CAN driver
  74. _can_driver = can_mgr->get_driver();
  75. if (_can_driver == nullptr) {
  76. debug_can(1, "KDECAN: no CAN driver\n\r");
  77. return;
  78. }
  79. // find available KDE ESCs
  80. frame_id_t id = { { .object_address = ESC_INFO_OBJ_ADDR,
  81. .destination_id = BROADCAST_NODE_ID,
  82. .source_id = AUTOPILOT_NODE_ID,
  83. .priority = 0,
  84. .unused = 0 } };
  85. uavcan::CanFrame frame { (id.value | uavcan::CanFrame::FlagEFF), nullptr, 0 };
  86. if(!_can_driver->getIface(CAN_IFACE_INDEX)->send(frame, uavcan::MonotonicTime::fromMSec(AP_HAL::millis() + 1000), 0)) {
  87. debug_can(1, "KDECAN: couldn't send discovery message\n\r");
  88. return;
  89. }
  90. debug_can(2, "KDECAN: discovery message sent\n\r");
  91. uint32_t start = AP_HAL::millis();
  92. // wait 1 second for answers
  93. while (AP_HAL::millis() - start < 1000) {
  94. uavcan::CanFrame esc_id_frame {};
  95. uavcan::MonotonicTime time {};
  96. uavcan::UtcTime utc_time {};
  97. uavcan::CanIOFlags flags {};
  98. int16_t n = _can_driver->getIface(CAN_IFACE_INDEX)->receive(esc_id_frame, time, utc_time, flags);
  99. if (n != 1) {
  100. continue;
  101. }
  102. if (!esc_id_frame.isExtended()) {
  103. continue;
  104. }
  105. if (esc_id_frame.dlc != 5) {
  106. continue;
  107. }
  108. id.value = esc_id_frame.id & uavcan::CanFrame::MaskExtID;
  109. if (id.source_id == BROADCAST_NODE_ID ||
  110. id.source_id >= (KDECAN_MAX_NUM_ESCS + ESC_NODE_ID_FIRST) ||
  111. id.destination_id != AUTOPILOT_NODE_ID ||
  112. id.object_address != ESC_INFO_OBJ_ADDR) {
  113. continue;
  114. }
  115. _esc_present_bitmask |= (1 << (id.source_id - ESC_NODE_ID_FIRST));
  116. _esc_max_node_id = id.source_id - ESC_NODE_ID_FIRST + 1;
  117. debug_can(2, "KDECAN: found ESC id %u\n\r", id.source_id);
  118. }
  119. snprintf(_thread_name, sizeof(_thread_name), "kdecan_%u", driver_index);
  120. // start thread for receiving and sending CAN frames
  121. if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_KDECAN::loop, void), _thread_name, 4096, AP_HAL::Scheduler::PRIORITY_CAN, 0)) {
  122. debug_can(1, "KDECAN: couldn't create thread\n\r");
  123. return;
  124. }
  125. _initialized = true;
  126. debug_can(2, "KDECAN: init done\n\r");
  127. return;
  128. }
  129. void AP_KDECAN::loop()
  130. {
  131. uavcan::MonotonicTime timeout;
  132. uavcan::CanFrame empty_frame { (0 | uavcan::CanFrame::FlagEFF), nullptr, 0 };
  133. const uavcan::CanFrame* select_frames[uavcan::MaxCanIfaces] { };
  134. select_frames[CAN_IFACE_INDEX] = &empty_frame;
  135. uint16_t output_buffer[KDECAN_MAX_NUM_ESCS] {};
  136. enumeration_state_t enumeration_state = _enumeration_state;
  137. uint64_t enumeration_start = 0;
  138. uint8_t enumeration_esc_num = 0;
  139. const uint32_t LOOP_INTERVAL_US = MIN(AP::scheduler().get_loop_period_us(), SET_PWM_MIN_INTERVAL_US);
  140. uint64_t pwm_last_sent = 0;
  141. uint8_t sending_esc_num = 0;
  142. uint64_t telemetry_last_request = 0;
  143. while (true) {
  144. if (!_initialized) {
  145. debug_can(2, "KDECAN: not initialized\n\r");
  146. hal.scheduler->delay_microseconds(2000);
  147. continue;
  148. }
  149. uavcan::CanSelectMasks inout_mask;
  150. uint64_t now = AP_HAL::micros64();
  151. // get latest enumeration state set from GCS
  152. if (_enum_sem.take(1)) {
  153. enumeration_state = _enumeration_state;
  154. _enum_sem.give();
  155. } else {
  156. debug_can(2, "KDECAN: failed to get enumeration semaphore on loop\n\r");
  157. }
  158. if (enumeration_state != ENUMERATION_STOPPED) {
  159. // check if enumeration timed out
  160. if (enumeration_start != 0 && now - enumeration_start >= ENUMERATION_TIMEOUT_MS * 1000) {
  161. enumeration_start = 0;
  162. WITH_SEMAPHORE(_enum_sem);
  163. // check if enumeration state didn't change or was set to stop
  164. if (enumeration_state == _enumeration_state || _enumeration_state == ENUMERATION_STOP) {
  165. enumeration_state = _enumeration_state = ENUMERATION_STOPPED;
  166. }
  167. continue;
  168. }
  169. timeout = uavcan::MonotonicTime::fromUSec(now + 1000);
  170. switch (enumeration_state) {
  171. case ENUMERATION_START: {
  172. inout_mask.write = 1 << CAN_IFACE_INDEX;
  173. // send broadcast frame to start enumeration
  174. frame_id_t id = { { .object_address = ENUM_OBJ_ADDR,
  175. .destination_id = BROADCAST_NODE_ID,
  176. .source_id = AUTOPILOT_NODE_ID,
  177. .priority = 0,
  178. .unused = 0 } };
  179. be16_t data = htobe16((uint16_t) ENUMERATION_TIMEOUT_MS);
  180. uavcan::CanFrame frame { (id.value | uavcan::CanFrame::FlagEFF), (uint8_t*) &data, sizeof(data) };
  181. uavcan::CanSelectMasks in_mask = inout_mask;
  182. select_frames[CAN_IFACE_INDEX] = &frame;
  183. // wait for write space to be available
  184. _can_driver->select(inout_mask, select_frames, timeout);
  185. select_frames[CAN_IFACE_INDEX] = &empty_frame;
  186. if (in_mask.write & inout_mask.write) {
  187. now = AP_HAL::micros64();
  188. timeout = uavcan::MonotonicTime::fromUSec(now + ENUMERATION_TIMEOUT_MS * 1000);
  189. int8_t res = _can_driver->getIface(CAN_IFACE_INDEX)->send(frame, timeout, 0);
  190. if (res == 1) {
  191. enumeration_start = now;
  192. enumeration_esc_num = 0;
  193. _esc_present_bitmask = 0;
  194. _esc_max_node_id = 0;
  195. WITH_SEMAPHORE(_enum_sem);
  196. if (enumeration_state == _enumeration_state) {
  197. enumeration_state = _enumeration_state = ENUMERATION_RUNNING;
  198. }
  199. } else if (res == 0) {
  200. debug_can(1, "KDECAN: strange buffer full when starting ESC enumeration\n\r");
  201. break;
  202. } else {
  203. debug_can(1, "KDECAN: error sending message to start ESC enumeration, result %d\n\r", res);
  204. break;
  205. }
  206. } else {
  207. break;
  208. }
  209. FALLTHROUGH;
  210. }
  211. case ENUMERATION_RUNNING: {
  212. inout_mask.read = 1 << CAN_IFACE_INDEX;
  213. inout_mask.write = 0;
  214. // wait for enumeration messages from ESCs
  215. uavcan::CanSelectMasks in_mask = inout_mask;
  216. _can_driver->select(inout_mask, select_frames, timeout);
  217. if (in_mask.read & inout_mask.read) {
  218. uavcan::CanFrame recv_frame;
  219. uavcan::MonotonicTime time;
  220. uavcan::UtcTime utc_time;
  221. uavcan::CanIOFlags flags {};
  222. int16_t res = _can_driver->getIface(CAN_IFACE_INDEX)->receive(recv_frame, time, utc_time, flags);
  223. if (res == 1) {
  224. if (time.toUSec() < enumeration_start) {
  225. // old message
  226. break;
  227. }
  228. frame_id_t id { .value = recv_frame.id & uavcan::CanFrame::MaskExtID };
  229. if (id.object_address == UPDATE_NODE_ID_OBJ_ADDR) {
  230. // reply from setting new node ID
  231. _esc_present_bitmask |= 1 << (id.source_id - ESC_NODE_ID_FIRST);
  232. _esc_max_node_id = MAX(_esc_max_node_id, id.source_id - ESC_NODE_ID_FIRST + 1);
  233. break;
  234. } else if (id.object_address != ENUM_OBJ_ADDR) {
  235. // discardable frame, only looking for enumeration
  236. break;
  237. }
  238. // try to set node ID for the received ESC
  239. while (AP_HAL::micros64() - enumeration_start < ENUMERATION_TIMEOUT_MS * 1000) {
  240. inout_mask.read = 0;
  241. inout_mask.write = 1 << CAN_IFACE_INDEX;
  242. // wait for write space to be available
  243. in_mask = inout_mask;
  244. _can_driver->select(inout_mask, select_frames, timeout);
  245. if (in_mask.write & inout_mask.write) {
  246. id = { { .object_address = UPDATE_NODE_ID_OBJ_ADDR,
  247. .destination_id = uint8_t(enumeration_esc_num + ESC_NODE_ID_FIRST),
  248. .source_id = AUTOPILOT_NODE_ID,
  249. .priority = 0,
  250. .unused = 0 } };
  251. uavcan::CanFrame send_frame { (id.value | uavcan::CanFrame::FlagEFF), (uint8_t*) &recv_frame.data, recv_frame.dlc };
  252. timeout = uavcan::MonotonicTime::fromUSec(enumeration_start + ENUMERATION_TIMEOUT_MS * 1000);
  253. res = _can_driver->getIface(CAN_IFACE_INDEX)->send(send_frame, timeout, 0);
  254. if (res == 1) {
  255. enumeration_esc_num++;
  256. break;
  257. } else if (res == 0) {
  258. debug_can(1, "KDECAN: strange buffer full when setting ESC node ID\n\r");
  259. } else {
  260. debug_can(1, "KDECAN: error sending message to set ESC node ID, result %d\n\r", res);
  261. }
  262. }
  263. }
  264. } else if (res == 0) {
  265. debug_can(1, "KDECAN: strange failed read when getting ESC enumeration message\n\r");
  266. } else {
  267. debug_can(1, "KDECAN: error receiving ESC enumeration message, result %d\n\r", res);
  268. }
  269. }
  270. break;
  271. }
  272. case ENUMERATION_STOP: {
  273. inout_mask.write = 1 << CAN_IFACE_INDEX;
  274. // send broadcast frame to stop enumeration
  275. frame_id_t id = { { .object_address = ENUM_OBJ_ADDR,
  276. .destination_id = BROADCAST_NODE_ID,
  277. .source_id = AUTOPILOT_NODE_ID,
  278. .priority = 0,
  279. .unused = 0 } };
  280. le16_t data = htole16((uint16_t) ENUMERATION_TIMEOUT_MS);
  281. uavcan::CanFrame frame { (id.value | uavcan::CanFrame::FlagEFF), (uint8_t*) &data, sizeof(data) };
  282. uavcan::CanSelectMasks in_mask = inout_mask;
  283. select_frames[CAN_IFACE_INDEX] = &frame;
  284. // wait for write space to be available
  285. _can_driver->select(inout_mask, select_frames, timeout);
  286. select_frames[CAN_IFACE_INDEX] = &empty_frame;
  287. if (in_mask.write & inout_mask.write) {
  288. timeout = uavcan::MonotonicTime::fromUSec(enumeration_start + ENUMERATION_TIMEOUT_MS * 1000);
  289. int8_t res = _can_driver->getIface(CAN_IFACE_INDEX)->send(frame, timeout, 0);
  290. if (res == 1) {
  291. enumeration_start = 0;
  292. WITH_SEMAPHORE(_enum_sem);
  293. if (enumeration_state == _enumeration_state) {
  294. enumeration_state = _enumeration_state = ENUMERATION_STOPPED;
  295. }
  296. } else if (res == 0) {
  297. debug_can(1, "KDECAN: strange buffer full when stop ESC enumeration\n\r");
  298. } else {
  299. debug_can(1, "KDECAN: error sending message to stop ESC enumeration, result %d\n\r", res);
  300. }
  301. }
  302. break;
  303. }
  304. case ENUMERATION_STOPPED:
  305. default:
  306. debug_can(2, "KDECAN: something wrong happened, shouldn't be here, enumeration state: %u\n\r", enumeration_state);
  307. break;
  308. }
  309. continue;
  310. }
  311. if (!_esc_present_bitmask) {
  312. debug_can(1, "KDECAN: no valid ESC present");
  313. hal.scheduler->delay(1000);
  314. continue;
  315. }
  316. // always look for received frames
  317. inout_mask.read = 1 << CAN_IFACE_INDEX;
  318. timeout = uavcan::MonotonicTime::fromUSec(now + LOOP_INTERVAL_US);
  319. // check if:
  320. // - is currently sending throttle frames, OR
  321. // - there are new output values and, a throttle frame was never sent or it's no longer in CAN queue, OR
  322. // - it is time to send throttle frames again, regardless of new output values, OR
  323. // - it is time to ask for telemetry information
  324. if (sending_esc_num > 0 ||
  325. (_new_output.load(std::memory_order_acquire) && (pwm_last_sent == 0 || now - pwm_last_sent > SET_PWM_TIMEOUT_US)) ||
  326. (pwm_last_sent != 0 && (now - pwm_last_sent > SET_PWM_MIN_INTERVAL_US)) ||
  327. (now - telemetry_last_request > TELEMETRY_INTERVAL_US)) {
  328. inout_mask.write = 1 << CAN_IFACE_INDEX;
  329. } else { // don't need to send frame, choose the maximum time we'll wait for receiving a frame
  330. uint64_t next_action = MIN(now + LOOP_INTERVAL_US, telemetry_last_request + TELEMETRY_INTERVAL_US);
  331. if (pwm_last_sent != 0) {
  332. next_action = MIN(next_action, pwm_last_sent + SET_PWM_MIN_INTERVAL_US);
  333. }
  334. timeout = uavcan::MonotonicTime::fromUSec(next_action);
  335. }
  336. // wait for write space or receive frame
  337. uavcan::CanSelectMasks in_mask = inout_mask;
  338. _can_driver->select(inout_mask, select_frames, timeout);
  339. if (in_mask.read & inout_mask.read) {
  340. uavcan::CanFrame frame;
  341. uavcan::MonotonicTime time;
  342. uavcan::UtcTime utc_time;
  343. uavcan::CanIOFlags flags {};
  344. int16_t res = _can_driver->getIface(CAN_IFACE_INDEX)->receive(frame, time, utc_time, flags);
  345. if (res == 1) {
  346. frame_id_t id { .value = frame.id & uavcan::CanFrame::MaskExtID };
  347. // check if frame is valid: directed at autopilot, doesn't come from broadcast and ESC was detected before
  348. if (id.destination_id == AUTOPILOT_NODE_ID &&
  349. id.source_id != BROADCAST_NODE_ID &&
  350. (1 << (id.source_id - ESC_NODE_ID_FIRST) & _esc_present_bitmask)) {
  351. switch (id.object_address) {
  352. case TELEMETRY_OBJ_ADDR: {
  353. if (frame.dlc != 8) {
  354. break;
  355. }
  356. if (!_telem_sem.take(1)) {
  357. debug_can(2, "KDECAN: failed to get telemetry semaphore on write\n\r");
  358. break;
  359. }
  360. _telemetry[id.source_id - ESC_NODE_ID_FIRST].time = time.toUSec();
  361. _telemetry[id.source_id - ESC_NODE_ID_FIRST].voltage = frame.data[0] << 8 | frame.data[1];
  362. _telemetry[id.source_id - ESC_NODE_ID_FIRST].current = frame.data[2] << 8 | frame.data[3];
  363. _telemetry[id.source_id - ESC_NODE_ID_FIRST].rpm = frame.data[4] << 8 | frame.data[5];
  364. _telemetry[id.source_id - ESC_NODE_ID_FIRST].temp = frame.data[6];
  365. _telemetry[id.source_id - ESC_NODE_ID_FIRST].new_data = true;
  366. _telem_sem.give();
  367. break;
  368. }
  369. default:
  370. // discard frame
  371. break;
  372. }
  373. }
  374. }
  375. }
  376. if (in_mask.write & inout_mask.write) {
  377. now = AP_HAL::micros64();
  378. bool new_output = _new_output.load(std::memory_order_acquire);
  379. if (sending_esc_num > 0) {
  380. // currently sending throttle frames, check it didn't timeout
  381. if (now - pwm_last_sent > SET_PWM_TIMEOUT_US) {
  382. debug_can(2, "KDECAN: timed-out after sending frame to ESC with ID %d\n\r", sending_esc_num - 1);
  383. sending_esc_num = 0;
  384. }
  385. }
  386. if (sending_esc_num == 0 && new_output) {
  387. if (!_rc_out_sem.take(1)) {
  388. debug_can(2, "KDECAN: failed to get PWM semaphore on read\n\r");
  389. continue;
  390. }
  391. memcpy(output_buffer, _scaled_output, KDECAN_MAX_NUM_ESCS * sizeof(uint16_t));
  392. _rc_out_sem.give();
  393. }
  394. // check if:
  395. // - is currently sending throttle frames, OR
  396. // - there are new output values and, a throttle frame was never sent or it's no longer in CAN queue, OR
  397. // - it is time to send throttle frames again, regardless of new output values
  398. if (sending_esc_num > 0 ||
  399. (new_output && (pwm_last_sent == 0 || now - pwm_last_sent > SET_PWM_TIMEOUT_US)) ||
  400. (pwm_last_sent != 0 && (now - pwm_last_sent > SET_PWM_MIN_INTERVAL_US))) {
  401. for (uint8_t esc_num = sending_esc_num; esc_num < _esc_max_node_id; esc_num++) {
  402. if ((_esc_present_bitmask & (1 << esc_num)) == 0) {
  403. continue;
  404. }
  405. be16_t kde_pwm = htobe16(output_buffer[esc_num]);
  406. if (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {
  407. kde_pwm = 0;
  408. }
  409. frame_id_t id = { { .object_address = SET_PWM_OBJ_ADDR,
  410. .destination_id = uint8_t(esc_num + ESC_NODE_ID_FIRST),
  411. .source_id = AUTOPILOT_NODE_ID,
  412. .priority = 0,
  413. .unused = 0 } };
  414. uavcan::CanFrame frame { (id.value | uavcan::CanFrame::FlagEFF), (uint8_t*) &kde_pwm, sizeof(kde_pwm) };
  415. if (esc_num == 0) {
  416. timeout = uavcan::MonotonicTime::fromUSec(now + SET_PWM_TIMEOUT_US);
  417. } else {
  418. timeout = uavcan::MonotonicTime::fromUSec(pwm_last_sent + SET_PWM_TIMEOUT_US);
  419. }
  420. int8_t res = _can_driver->getIface(CAN_IFACE_INDEX)->send(frame, timeout, 0);
  421. if (res == 1) {
  422. if (esc_num == 0) {
  423. pwm_last_sent = now;
  424. if (new_output) {
  425. _new_output.store(false, std::memory_order_release);
  426. }
  427. }
  428. sending_esc_num = (esc_num + 1) % _esc_max_node_id;
  429. } else if (res == 0) {
  430. debug_can(1, "KDECAN: strange buffer full when sending message to ESC with ID %d\n\r", esc_num + ESC_NODE_ID_FIRST);
  431. } else {
  432. debug_can(1, "KDECAN: error sending message to ESC with ID %d, result %d\n\r", esc_num + ESC_NODE_ID_FIRST, res);
  433. }
  434. break;
  435. }
  436. } else if (now - telemetry_last_request > TELEMETRY_INTERVAL_US) {
  437. // broadcast telemetry request frame
  438. frame_id_t id = { { .object_address = TELEMETRY_OBJ_ADDR,
  439. .destination_id = BROADCAST_NODE_ID,
  440. .source_id = AUTOPILOT_NODE_ID,
  441. .priority = 0,
  442. .unused = 0 } };
  443. uavcan::CanFrame frame { (id.value | uavcan::CanFrame::FlagEFF), nullptr, 0 };
  444. timeout = uavcan::MonotonicTime::fromUSec(now + TELEMETRY_TIMEOUT_US);
  445. int8_t res = _can_driver->getIface(CAN_IFACE_INDEX)->send(frame, timeout, 0);
  446. if (res == 1) {
  447. telemetry_last_request = now;
  448. } else if (res == 0) {
  449. debug_can(1, "KDECAN: strange buffer full when sending message requesting telemetry\n\r");
  450. } else {
  451. debug_can(1, "KDECAN: error sending message requesting telemetry, result %d\n\r", res);
  452. }
  453. }
  454. }
  455. }
  456. }
  457. void AP_KDECAN::update()
  458. {
  459. if (_rc_out_sem.take(1)) {
  460. for (uint8_t i = 0; i < KDECAN_MAX_NUM_ESCS; i++) {
  461. if ((_esc_present_bitmask & (1 << i)) == 0) {
  462. continue;
  463. }
  464. SRV_Channel::Aux_servo_function_t motor_function = SRV_Channels::get_motor_function(i);
  465. if (SRV_Channels::function_assigned(motor_function)) {
  466. float norm_output = SRV_Channels::get_output_norm(motor_function);
  467. _scaled_output[i] = uint16_t((norm_output + 1.0f) / 2.0f * 2000.0f);
  468. } else {
  469. _scaled_output[i] = 0;
  470. }
  471. }
  472. _rc_out_sem.give();
  473. _new_output.store(true, std::memory_order_release);
  474. } else {
  475. debug_can(2, "KDECAN: failed to get PWM semaphore on write\n\r");
  476. }
  477. AP_Logger *logger = AP_Logger::get_singleton();
  478. if (logger == nullptr || !logger->should_log(0xFFFFFFFF)) {
  479. return;
  480. }
  481. if (!_telem_sem.take(1)) {
  482. debug_can(2, "KDECAN: failed to get telemetry semaphore on DF read\n\r");
  483. return;
  484. }
  485. telemetry_info_t telem_buffer[KDECAN_MAX_NUM_ESCS] {};
  486. for (uint8_t i = 0; i < _esc_max_node_id; i++) {
  487. if (_telemetry[i].new_data) {
  488. telem_buffer[i] = _telemetry[i];
  489. _telemetry[i].new_data = false;
  490. }
  491. }
  492. _telem_sem.give();
  493. uint8_t num_poles = _num_poles > 0 ? _num_poles : DEFAULT_NUM_POLES;
  494. // log ESC telemetry data
  495. for (uint8_t i = 0; i < _esc_max_node_id; i++) {
  496. if (telem_buffer[i].new_data) {
  497. logger->Write_ESC(i, telem_buffer[i].time,
  498. int32_t(telem_buffer[i].rpm * 60UL * 2 / num_poles * 100),
  499. telem_buffer[i].voltage,
  500. telem_buffer[i].current,
  501. int16_t(telem_buffer[i].temp * 100U), 0);
  502. }
  503. }
  504. }
  505. bool AP_KDECAN::pre_arm_check(const char* &reason)
  506. {
  507. if (!_enum_sem.take(1)) {
  508. debug_can(2, "KDECAN: failed to get enumeration semaphore on read\n\r");
  509. reason = "KDECAN enumeration state unknown";
  510. return false;
  511. }
  512. if (_enumeration_state != ENUMERATION_STOPPED) {
  513. reason = "KDECAN enumeration running";
  514. _enum_sem.give();
  515. return false;
  516. }
  517. _enum_sem.give();
  518. uint16_t motors_mask = 0;
  519. AP_Motors *motors = AP_Motors::get_singleton();
  520. if (motors) {
  521. motors_mask = motors->get_motor_mask();
  522. }
  523. uint8_t num_expected_motors = __builtin_popcount(motors_mask);
  524. uint8_t num_present_escs = __builtin_popcount(_esc_present_bitmask);
  525. if (num_present_escs < num_expected_motors) {
  526. reason = "Not enough KDECAN ESCs detected";
  527. return false;
  528. }
  529. if (num_present_escs > num_expected_motors) {
  530. reason = "Too many KDECAN ESCs detected";
  531. return false;
  532. }
  533. if (_esc_max_node_id != num_expected_motors) {
  534. reason = "Wrong KDECAN node IDs, run enumeration";
  535. return false;
  536. }
  537. return true;
  538. }
  539. void AP_KDECAN::send_mavlink(uint8_t chan)
  540. {
  541. if (!_telem_sem.take(1)) {
  542. debug_can(2, "KDECAN: failed to get telemetry semaphore on MAVLink read\n\r");
  543. return;
  544. }
  545. telemetry_info_t telem_buffer[KDECAN_MAX_NUM_ESCS];
  546. memcpy(telem_buffer, _telemetry, sizeof(telemetry_info_t) * KDECAN_MAX_NUM_ESCS);
  547. _telem_sem.give();
  548. uint16_t voltage[4] {};
  549. uint16_t current[4] {};
  550. uint16_t rpm[4] {};
  551. uint8_t temperature[4] {};
  552. uint16_t totalcurrent[4] {};
  553. uint16_t count[4] {};
  554. uint8_t num_poles = _num_poles > 0 ? _num_poles : DEFAULT_NUM_POLES;
  555. uint64_t now = AP_HAL::micros64();
  556. for (uint8_t i = 0; i < _esc_max_node_id && i < 8; i++) {
  557. uint8_t idx = i % 4;
  558. if (telem_buffer[i].time && (now - telem_buffer[i].time < 1000000)) {
  559. voltage[idx] = telem_buffer[i].voltage;
  560. current[idx] = telem_buffer[i].current;
  561. rpm[idx] = uint16_t(telem_buffer[i].rpm * 60UL * 2 / num_poles);
  562. temperature[idx] = telem_buffer[i].temp;
  563. } else {
  564. voltage[idx] = 0;
  565. current[idx] = 0;
  566. rpm[idx] = 0;
  567. temperature[idx] = 0;
  568. }
  569. if (idx == 3 || i == _esc_max_node_id - 1) {
  570. if (!HAVE_PAYLOAD_SPACE((mavlink_channel_t)chan, ESC_TELEMETRY_1_TO_4)) {
  571. return;
  572. }
  573. if (i < 4) {
  574. mavlink_msg_esc_telemetry_1_to_4_send((mavlink_channel_t)chan, temperature, voltage, current, totalcurrent, rpm, count);
  575. } else {
  576. mavlink_msg_esc_telemetry_5_to_8_send((mavlink_channel_t)chan, temperature, voltage, current, totalcurrent, rpm, count);
  577. }
  578. }
  579. }
  580. }
  581. bool AP_KDECAN::run_enumeration(bool start_stop)
  582. {
  583. if (!_enum_sem.take(1)) {
  584. debug_can(2, "KDECAN: failed to get enumeration semaphore on write\n\r");
  585. return false;
  586. }
  587. if (start_stop) {
  588. _enumeration_state = ENUMERATION_START;
  589. } else if (_enumeration_state != ENUMERATION_STOPPED) {
  590. _enumeration_state = ENUMERATION_STOP;
  591. }
  592. _enum_sem.give();
  593. return true;
  594. }
  595. #endif // HAL_WITH_UAVCAN