123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137 |
-
- #pragma once
- #include <AP_HAL/CAN.h>
- #include <AP_HAL/Semaphores.h>
- #include <AP_Param/AP_Param.h>
- #include <atomic>
- #define KDECAN_MAX_NUM_ESCS 8
- class AP_KDECAN : public AP_HAL::CANProtocol {
- public:
- AP_KDECAN();
-
-
- AP_KDECAN(const AP_KDECAN &other) = delete;
- AP_KDECAN &operator=(const AP_KDECAN&) = delete;
- static const struct AP_Param::GroupInfo var_info[];
-
- static AP_KDECAN *get_kdecan(uint8_t driver_index);
- void init(uint8_t driver_index, bool enable_filters) override;
-
- void update();
-
-
- bool pre_arm_check(const char* &reason);
-
- void send_mavlink(uint8_t chan);
-
-
- bool run_enumeration(bool start_stop);
- private:
- void loop();
- bool _initialized;
- char _thread_name[9];
- uint8_t _driver_index;
- uavcan::ICanDriver* _can_driver;
- AP_Int8 _num_poles;
-
- uint16_t _esc_present_bitmask;
- uint8_t _esc_max_node_id;
-
- HAL_Semaphore _enum_sem;
- enum enumeration_state_t : uint8_t {
- ENUMERATION_STOPPED,
- ENUMERATION_START,
- ENUMERATION_STOP,
- ENUMERATION_RUNNING
- } _enumeration_state = ENUMERATION_STOPPED;
-
- HAL_Semaphore _rc_out_sem;
- std::atomic<bool> _new_output;
- uint16_t _scaled_output[KDECAN_MAX_NUM_ESCS];
-
- HAL_Semaphore _telem_sem;
- struct telemetry_info_t {
- uint64_t time;
- uint16_t voltage;
- uint16_t current;
- uint16_t rpm;
- uint8_t temp;
- bool new_data;
- } _telemetry[KDECAN_MAX_NUM_ESCS];
- union frame_id_t {
- struct {
- uint8_t object_address;
- uint8_t destination_id;
- uint8_t source_id;
- uint8_t priority:5;
- uint8_t unused:3;
- };
- uint32_t value;
- };
-
- static const uint8_t AUTOPILOT_NODE_ID = 0;
- static const uint8_t BROADCAST_NODE_ID = 1;
- static const uint8_t ESC_NODE_ID_FIRST = 2;
- static const uint8_t ESC_INFO_OBJ_ADDR = 0;
- static const uint8_t SET_PWM_OBJ_ADDR = 1;
- static const uint8_t VOLTAGE_OBJ_ADDR = 2;
- static const uint8_t CURRENT_OBJ_ADDR = 3;
- static const uint8_t RPM_OBJ_ADDR = 4;
- static const uint8_t TEMPERATURE_OBJ_ADDR = 5;
- static const uint8_t GET_PWM_INPUT_OBJ_ADDR = 6;
- static const uint8_t GET_PWM_OUTPUT_OBJ_ADDR = 7;
- static const uint8_t MCU_ID_OBJ_ADDR = 8;
- static const uint8_t UPDATE_NODE_ID_OBJ_ADDR = 9;
- static const uint8_t ENUM_OBJ_ADDR = 10;
- static const uint8_t TELEMETRY_OBJ_ADDR = 11;
- static const uint16_t SET_PWM_MIN_INTERVAL_US = 2500;
- static const uint32_t TELEMETRY_INTERVAL_US = 100000;
- static const uint32_t SET_PWM_TIMEOUT_US = 2000;
- static const uint16_t TELEMETRY_TIMEOUT_US = 500;
- static const uint16_t ENUMERATION_TIMEOUT_MS = 30000;
- static const uint8_t CAN_IFACE_INDEX = 0;
- };
|