AP_KDECAN.h 3.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137
  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.h
  15. *
  16. * Author: Francisco Ferreira
  17. */
  18. #pragma once
  19. #include <AP_HAL/CAN.h>
  20. #include <AP_HAL/Semaphores.h>
  21. #include <AP_Param/AP_Param.h>
  22. #include <atomic>
  23. // there are 12 motor functions in SRV_Channel but CAN driver can't keep up
  24. #define KDECAN_MAX_NUM_ESCS 8
  25. class AP_KDECAN : public AP_HAL::CANProtocol {
  26. public:
  27. AP_KDECAN();
  28. /* Do not allow copies */
  29. AP_KDECAN(const AP_KDECAN &other) = delete;
  30. AP_KDECAN &operator=(const AP_KDECAN&) = delete;
  31. static const struct AP_Param::GroupInfo var_info[];
  32. // Return KDECAN from @driver_index or nullptr if it's not ready or doesn't exist
  33. static AP_KDECAN *get_kdecan(uint8_t driver_index);
  34. void init(uint8_t driver_index, bool enable_filters) override;
  35. // called from SRV_Channels
  36. void update();
  37. // check that arming can happen
  38. bool pre_arm_check(const char* &reason);
  39. // send MAVLink telemetry packets
  40. void send_mavlink(uint8_t chan);
  41. // caller checks that vehicle isn't armed
  42. // start_stop: true to start, false to stop
  43. bool run_enumeration(bool start_stop);
  44. private:
  45. void loop();
  46. bool _initialized;
  47. char _thread_name[9];
  48. uint8_t _driver_index;
  49. uavcan::ICanDriver* _can_driver;
  50. AP_Int8 _num_poles;
  51. // ESC detected information
  52. uint16_t _esc_present_bitmask;
  53. uint8_t _esc_max_node_id;
  54. // enumeration
  55. HAL_Semaphore _enum_sem;
  56. enum enumeration_state_t : uint8_t {
  57. ENUMERATION_STOPPED,
  58. ENUMERATION_START,
  59. ENUMERATION_STOP,
  60. ENUMERATION_RUNNING
  61. } _enumeration_state = ENUMERATION_STOPPED;
  62. // PWM output
  63. HAL_Semaphore _rc_out_sem;
  64. std::atomic<bool> _new_output;
  65. uint16_t _scaled_output[KDECAN_MAX_NUM_ESCS];
  66. // telemetry input
  67. HAL_Semaphore _telem_sem;
  68. struct telemetry_info_t {
  69. uint64_t time;
  70. uint16_t voltage;
  71. uint16_t current;
  72. uint16_t rpm;
  73. uint8_t temp;
  74. bool new_data;
  75. } _telemetry[KDECAN_MAX_NUM_ESCS];
  76. union frame_id_t {
  77. struct {
  78. uint8_t object_address;
  79. uint8_t destination_id;
  80. uint8_t source_id;
  81. uint8_t priority:5;
  82. uint8_t unused:3;
  83. };
  84. uint32_t value;
  85. };
  86. static const uint8_t AUTOPILOT_NODE_ID = 0;
  87. static const uint8_t BROADCAST_NODE_ID = 1;
  88. static const uint8_t ESC_NODE_ID_FIRST = 2;
  89. static const uint8_t ESC_INFO_OBJ_ADDR = 0;
  90. static const uint8_t SET_PWM_OBJ_ADDR = 1;
  91. static const uint8_t VOLTAGE_OBJ_ADDR = 2;
  92. static const uint8_t CURRENT_OBJ_ADDR = 3;
  93. static const uint8_t RPM_OBJ_ADDR = 4;
  94. static const uint8_t TEMPERATURE_OBJ_ADDR = 5;
  95. static const uint8_t GET_PWM_INPUT_OBJ_ADDR = 6;
  96. static const uint8_t GET_PWM_OUTPUT_OBJ_ADDR = 7;
  97. static const uint8_t MCU_ID_OBJ_ADDR = 8;
  98. static const uint8_t UPDATE_NODE_ID_OBJ_ADDR = 9;
  99. static const uint8_t ENUM_OBJ_ADDR = 10;
  100. static const uint8_t TELEMETRY_OBJ_ADDR = 11;
  101. static const uint16_t SET_PWM_MIN_INTERVAL_US = 2500;
  102. static const uint32_t TELEMETRY_INTERVAL_US = 100000;
  103. static const uint32_t SET_PWM_TIMEOUT_US = 2000;
  104. static const uint16_t TELEMETRY_TIMEOUT_US = 500;
  105. static const uint16_t ENUMERATION_TIMEOUT_MS = 30000;
  106. static const uint8_t CAN_IFACE_INDEX = 0;
  107. };