CANSerialRouter.cpp 4.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149
  1. /*
  2. * This file is free software: you can redistribute it and/or modify it
  3. * under the terms of the GNU General Public License as published by the
  4. * Free Software Foundation, either version 3 of the License, or
  5. * (at your option) any later version.
  6. *
  7. * This file is distributed in the hope that it will be useful, but
  8. * WITHOUT ANY WARRANTY; without even the implied warranty of
  9. * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
  10. * See the GNU General Public License for more details.
  11. *
  12. * You should have received a copy of the GNU General Public License along
  13. * with this program. If not, see <http://www.gnu.org/licenses/>.
  14. *
  15. * Siddharth Bharat Purohit
  16. */
  17. #include "CANSerialRouter.h"
  18. #if AP_UAVCAN_SLCAN_ENABLED
  19. #include <AP_SerialManager/AP_SerialManager.h>
  20. #include <AP_BoardConfig/AP_BoardConfig_CAN.h>
  21. extern const AP_HAL::HAL& hal;
  22. void SLCANRouter::init(ChibiOS_CAN::CanIface* can_if, ChibiOS_CAN::BusEvent* update_event)
  23. {
  24. _can_if = can_if;
  25. _update_event = update_event;
  26. hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&SLCANRouter::timer, void));
  27. }
  28. void SLCANRouter::run()
  29. {
  30. _port = AP::can().get_slcan_serial();
  31. if (_port == nullptr) {
  32. return;
  33. }
  34. if (_slcan_if.init(921600, SLCAN::CAN::OperatingMode::NormalMode, _port) < 0) {
  35. return;
  36. }
  37. _slcan_rt_timeout = AP::can().get_slcan_timeout();
  38. if (!_thread_started) {
  39. hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&SLCANRouter::can2slcan_router_trampoline, void), "C2SRouter", 512, AP_HAL::Scheduler::PRIORITY_CAN, 0);
  40. hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&SLCANRouter::slcan2can_router_trampoline, void), "S2CRouter", 512, AP_HAL::Scheduler::PRIORITY_CAN, 0);
  41. _thread_started = true;
  42. _thread_suspended = false;
  43. }
  44. else if (_thread_suspended) { //wake up threads
  45. chSysLock();
  46. if (_c2s_thd_ref && _s2c_thd_ref) {
  47. chThdResumeS(&_c2s_thd_ref, MSG_OK);
  48. chThdResumeS(&_s2c_thd_ref, MSG_OK);
  49. _thread_suspended = false;
  50. }
  51. chSysUnlock();
  52. }
  53. }
  54. void SLCANRouter::timer()
  55. {
  56. if ((!_thread_started || _thread_suspended) && (AP::can().get_slcan_serial() != nullptr)) {
  57. run();
  58. AP::can().reset_slcan_serial();
  59. _last_active_time = AP_HAL::millis();
  60. }
  61. if (!_slcan_if.closed()) {
  62. _last_active_time = AP_HAL::millis();
  63. }
  64. if (_thread_suspended) {
  65. return;
  66. }
  67. if (AP_HAL::millis() - _last_active_time > (_slcan_rt_timeout * 1000) && _slcan_rt_timeout != 0) {
  68. chSysLock();
  69. _port->lock_port(0, 0);
  70. _port->flush();
  71. _thread_suspended = true;
  72. chSysUnlock();
  73. }
  74. }
  75. void SLCANRouter::route_frame_to_slcan(ChibiOS_CAN::CanIface* can_if, const uavcan::CanFrame& frame, uint64_t timestamp_usec)
  76. {
  77. if (_can_if != can_if) {
  78. return;
  79. }
  80. CanRouteItem it;
  81. it.frame = frame;
  82. it.utc_usec = timestamp_usec;
  83. if (_slcan_tx_queue.space() == 0) {
  84. _slcan_tx_queue.pop();
  85. }
  86. _slcan_tx_queue.push(it);
  87. }
  88. void SLCANRouter::route_frame_to_can(const uavcan::CanFrame& frame, uint64_t timestamp_usec)
  89. {
  90. CanRouteItem it;
  91. it.frame = frame;
  92. it.utc_usec = timestamp_usec;
  93. if (_can_tx_queue.space() == 0) {
  94. _can_tx_queue.pop();
  95. }
  96. _can_tx_queue.push(it);
  97. }
  98. void SLCANRouter::slcan2can_router_trampoline(void)
  99. {
  100. CanRouteItem it;
  101. while (true) {
  102. chSysLock();
  103. _s2c_thd_ref = nullptr;
  104. if (_thread_suspended) {
  105. chThdSuspendS(&_s2c_thd_ref);
  106. _port->flush();
  107. }
  108. chSysUnlock();
  109. _slcan_if.reader();
  110. if (_can_tx_queue.available() && _can_if) {
  111. _can_tx_queue.peek(it);
  112. if (_can_if->send(it.frame, uavcan::MonotonicTime::fromUSec(AP_HAL::micros64() + 1000), 0)) {
  113. _can_tx_queue.pop();
  114. }
  115. }
  116. }
  117. }
  118. void SLCANRouter::can2slcan_router_trampoline(void)
  119. {
  120. CanRouteItem it;
  121. while (true) {
  122. chSysLock();
  123. _c2s_thd_ref = nullptr;
  124. if (_thread_suspended) {
  125. chThdSuspendS(&_c2s_thd_ref);
  126. }
  127. chSysUnlock();
  128. _update_event->wait(uavcan::MonotonicDuration::fromUSec(1000));
  129. if (_slcan_tx_queue.available()) {
  130. _slcan_tx_queue.peek(it);
  131. if (_slcan_if.send(it.frame, uavcan::MonotonicTime::fromUSec(AP_HAL::micros64() + 1000), 0)) {
  132. _slcan_tx_queue.pop();
  133. }
  134. }
  135. }
  136. }
  137. #endif