CANSerialRouter.h 2.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869
  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. #pragma once
  18. #include "AP_HAL_ChibiOS.h"
  19. #if AP_UAVCAN_SLCAN_ENABLED
  20. #include "CAN.h"
  21. #include <AP_UAVCAN/AP_UAVCAN_SLCAN.h>
  22. #include "CANThread.h"
  23. #include "CANClock.h"
  24. #include "CANIface.h"
  25. #define SLCAN_ROUTER_QUEUE_SIZE 64
  26. struct CanRouteItem {
  27. uint64_t utc_usec;
  28. uavcan::CanFrame frame;
  29. CanRouteItem() :
  30. utc_usec(0)
  31. {
  32. }
  33. };
  34. class SLCANRouter {
  35. ChibiOS_CAN::CanIface* _can_if;
  36. SLCAN::CAN _slcan_if;
  37. ObjectBuffer<CanRouteItem> _can_tx_queue;
  38. ObjectBuffer<CanRouteItem> _slcan_tx_queue;
  39. ChibiOS_CAN::BusEvent* _update_event;
  40. uint32_t _last_active_time = 0;
  41. uint32_t _slcan_rt_timeout = 0;
  42. bool _thread_started = false;
  43. bool _thread_suspended = false;
  44. HAL_Semaphore router_sem;
  45. thread_reference_t _s2c_thd_ref;
  46. thread_reference_t _c2s_thd_ref;
  47. void timer(void);
  48. AP_HAL::UARTDriver* _port;
  49. public:
  50. SLCANRouter() : _slcan_if(SLCAN_DRIVER_INDEX, SLCAN_RX_QUEUE_SIZE), _can_tx_queue(SLCAN_ROUTER_QUEUE_SIZE), _slcan_tx_queue(SLCAN_ROUTER_QUEUE_SIZE)
  51. {}
  52. void init(ChibiOS_CAN::CanIface* can_if, ChibiOS_CAN::BusEvent* update_event);
  53. void route_frame_to_slcan(ChibiOS_CAN::CanIface* can_if, const uavcan::CanFrame& frame, uint64_t timestamp_usec);
  54. void route_frame_to_can(const uavcan::CanFrame& frame, uint64_t timestamp_usec);
  55. void slcan2can_router_trampoline(void);
  56. void can2slcan_router_trampoline(void);
  57. void run(void);
  58. };
  59. #endif // AP_UAVCAN_SLCAN_ENABLED