AP_ToshibaCAN.h 4.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151
  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. #pragma once
  14. #include <AP_HAL/CAN.h>
  15. #include <AP_HAL/Semaphores.h>
  16. #define TOSHIBACAN_MAX_NUM_ESCS 12
  17. class AP_ToshibaCAN : public AP_HAL::CANProtocol {
  18. public:
  19. AP_ToshibaCAN();
  20. ~AP_ToshibaCAN();
  21. /* Do not allow copies */
  22. AP_ToshibaCAN(const AP_ToshibaCAN &other) = delete;
  23. AP_ToshibaCAN &operator=(const AP_ToshibaCAN&) = delete;
  24. // Return ToshibaCAN from @driver_index or nullptr if it's not ready or doesn't exist
  25. static AP_ToshibaCAN *get_tcan(uint8_t driver_index);
  26. // initialise ToshibaCAN bus
  27. void init(uint8_t driver_index, bool enable_filters) override;
  28. // called from SRV_Channels
  29. void update();
  30. // send ESC telemetry messages over MAVLink
  31. void send_esc_telemetry_mavlink(uint8_t mav_chan);
  32. private:
  33. // loop to send output to ESCs in background thread
  34. void loop();
  35. // write frame on CAN bus, returns true on success
  36. bool write_frame(uavcan::CanFrame &out_frame, uavcan::MonotonicTime timeout);
  37. // read frame on CAN bus, returns true on success
  38. bool read_frame(uavcan::CanFrame &recv_frame, uavcan::MonotonicTime timeout);
  39. bool _initialized;
  40. char _thread_name[9];
  41. uint8_t _driver_index;
  42. uavcan::ICanDriver* _can_driver;
  43. const uavcan::CanFrame* _select_frames[uavcan::MaxCanIfaces] { };
  44. // PWM output
  45. HAL_Semaphore _rc_out_sem;
  46. uint16_t _scaled_output[TOSHIBACAN_MAX_NUM_ESCS];
  47. uint16_t update_count; // counter increments each time main thread updates outputs
  48. uint16_t update_count_buffered; // counter when outputs copied to buffer before before sending to ESCs
  49. uint16_t update_count_sent; // counter of outputs successfully sent
  50. uint8_t send_stage; // stage of sending algorithm (each stage sends one frame to ESCs)
  51. // telemetry data (rpm, voltage)
  52. HAL_Semaphore _telem_sem;
  53. struct telemetry_info_t {
  54. uint16_t rpm;
  55. uint16_t millivolts;
  56. uint16_t temperature;
  57. uint16_t count;
  58. bool new_data;
  59. } _telemetry[TOSHIBACAN_MAX_NUM_ESCS];
  60. uint32_t _telemetry_req_ms; // system time (in milliseconds) to request data from escs (updated at 10hz)
  61. uint8_t _telemetry_temp_req_counter; // counter used to trigger temp data requests from ESCs (10x slower than other telem data)
  62. // bitmask of which escs seem to be present
  63. uint16_t _esc_present_bitmask;
  64. // structure for sending motor lock command to ESC
  65. union motor_lock_cmd_t {
  66. struct PACKED {
  67. uint8_t motor2:4;
  68. uint8_t motor1:4;
  69. uint8_t motor4:4;
  70. uint8_t motor3:4;
  71. uint8_t motor6:4;
  72. uint8_t motor5:4;
  73. uint8_t motor8:4;
  74. uint8_t motor7:4;
  75. uint8_t motor10:4;
  76. uint8_t motor9:4;
  77. uint8_t motor12:4;
  78. uint8_t motor11:4;
  79. };
  80. uint8_t data[6];
  81. };
  82. // structure for sending turn rate command to ESC
  83. union motor_rotation_cmd_t {
  84. struct PACKED {
  85. uint16_t motor4;
  86. uint16_t motor3;
  87. uint16_t motor2;
  88. uint16_t motor1;
  89. };
  90. uint8_t data[8];
  91. };
  92. // structure for requesting data from ESC
  93. union motor_request_data_cmd_t {
  94. struct PACKED {
  95. uint8_t motor2:4;
  96. uint8_t motor1:4;
  97. uint8_t motor4:4;
  98. uint8_t motor3:4;
  99. uint8_t motor6:4;
  100. uint8_t motor5:4;
  101. uint8_t motor8:4;
  102. uint8_t motor7:4;
  103. uint8_t motor10:4;
  104. uint8_t motor9:4;
  105. uint8_t motor12:4;
  106. uint8_t motor11:4;
  107. };
  108. uint8_t data[6];
  109. };
  110. // structure for replies from ESC of data1 (rpm and voltage)
  111. union motor_reply_data1_t {
  112. struct PACKED {
  113. uint8_t rxng:1;
  114. uint8_t state:7;
  115. uint16_t rpm;
  116. uint16_t reserved;
  117. uint16_t millivolts;
  118. uint8_t position_est_error;
  119. };
  120. uint8_t data[8];
  121. };
  122. // frames to be sent
  123. uavcan::CanFrame unlock_frame;
  124. uavcan::CanFrame mot_rot_frame1;
  125. uavcan::CanFrame mot_rot_frame2;
  126. uavcan::CanFrame mot_rot_frame3;
  127. };