123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322 |
- /*
- * This file is free software: you can redistribute it and/or modify it
- * under the terms of the GNU General Public License as published by the
- * Free Software Foundation, either version 3 of the License, or
- * (at your option) any later version.
- *
- * This file is distributed in the hope that it will be useful, but
- * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
- * See the GNU General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License along
- * with this program. If not, see <http://www.gnu.org/licenses/>.
- *
- * Author: Eugene Shamaev, Siddharth Bharat Purohit
- */
- #ifndef AP_UAVCAN_H_
- #define AP_UAVCAN_H_
- #include <uavcan/uavcan.hpp>
- #include <AP_HAL/CAN.h>
- #include <AP_HAL/Semaphores.h>
- #include <AP_Param/AP_Param.h>
- #include <uavcan/helpers/heap_based_pool_allocator.hpp>
- #include "AP_UAVCAN_Servers.h"
- #include "HVcallback.h"
- #ifndef UAVCAN_NODE_POOL_SIZE
- #define UAVCAN_NODE_POOL_SIZE 8192
- #endif
- #ifndef UAVCAN_NODE_POOL_BLOCK_SIZE
- #define UAVCAN_NODE_POOL_BLOCK_SIZE 64
- #endif
- #ifndef UAVCAN_SRV_NUMBER
- #define UAVCAN_SRV_NUMBER 18
- #endif
- #define AP_UAVCAN_SW_VERS_MAJOR 1
- #define AP_UAVCAN_SW_VERS_MINOR 0
- #define AP_UAVCAN_HW_VERS_MAJOR 1
- #define AP_UAVCAN_HW_VERS_MINOR 0
- #define AP_UAVCAN_MAX_LED_DEVICES 4
- #define HV_motor_number 3
- #define LV_motor_number 2
- // fwd-declare callback classes
- class ButtonCb;
- /*
- Frontend Backend-Registry Binder: Whenever a message of said DataType_ from new node is received,
- the Callback will invoke registery to register the node as separate backend.
- */
- #define UC_REGISTRY_BINDER(ClassName_, DataType_) \
- class ClassName_ : public AP_UAVCAN::RegistryBinder<DataType_> { \
- typedef void (*CN_Registry)(AP_UAVCAN*, uint8_t, const ClassName_&); \
- public: \
- ClassName_() : RegistryBinder() {} \
- ClassName_(AP_UAVCAN* uc, CN_Registry ffunc) : \
- RegistryBinder(uc, (Registry)ffunc) {} \
- }
- //---------selfdefine type start-------------
- struct DRIVEBOX_ABNORMAL
- {
- uint16_t drive0:8;
- uint16_t drive1:8;
-
- };
- union DRIVEBOX_ABNORMAL_UNI
- {
- uint16_t all;
- struct DRIVEBOX_ABNORMAL bit;
- };
- struct PROPELLER_MOTOR_ABNORMAL
- {//电机缠绕等级
- uint16_t motor0:4;
- uint16_t motor1:4;
- uint16_t motor2:4;
- uint16_t motor3:4;
- uint16_t motor4:4;
- uint16_t motor5:4;
- uint16_t motor6:4;
- uint16_t motor7:4;
-
- };
- //电机缠绕等级
- union PROPELLER_ABNORMAL_UNI
- {
- uint32_t all;
- struct PROPELLER_MOTOR_ABNORMAL bit;
- };
- struct STM32board_set_N25
- {
- float track_P;
- float track_I;
- float track_D;
- float brush_P;
- float brush_I;
- float brush_D;
- float Lowspeed_protect;
- float Highspeed_protect;
- int16_t Speed_seg;
- int16_t Max_current;
- int16_t Max_time;
- int16_t Reboot;
- uint8_t reverse_motor;
- };
- struct ESCTelemetryData {
- uint32_t error_count; //# Resets when the motor restarts
- float voltage; //# Volt
- float current; //# Ampere. Can be negative in case of a regenerative braking.
- float temperature; //#
- int32_t rpm; //# Negative value indicates reverse rotation
- uint8_t power_rating_pct;// # Instant demand factor in percent (percent of maximum power); range 0% to 127%.
- uint8_t esc_index;
- };
- //---------selfdefine type end-------------
- class AP_UAVCAN : public AP_HAL::CANProtocol {
- public:
- AP_UAVCAN();
- ~AP_UAVCAN();
- //--------self define start--------------------
- struct ESCTelemetryData thruster[6];
-
- struct HVmes HVmotor1;//高压电调1
- struct HVmes HVmotor2;//高压电调2
- struct HVmes HVmotor3;//高压电调3
- int16_t motor_from_stm32[12]; //STM32发来的数据
- uint16_t motor_stall_flag;//堵转标志
-
- uint32_t propellerblock_flag;//推进器缠绕
- int16_t temperature_48Vpower;//48V温度
- int16_t board_voltage;//48V电源
- int16_t driverleakstate;//驱动仓漏水
-
-
- static AP_UAVCAN *_singleton;
- static AP_UAVCAN *get_singleton() {
- return _singleton;
- }
-
-
- int16_t last_thrust_hv[HV_motor_number];
-
-
- //--------self define end--------------------
- static const struct AP_Param::GroupInfo var_info[];
- // Return uavcan from @driver_index or nullptr if it's not ready or doesn't exist
- static AP_UAVCAN *get_uavcan(uint8_t driver_index);
- void init(uint8_t driver_index, bool enable_filters) override;
- uavcan::Node<0>* get_node() { return _node; }
- uint8_t get_driver_index() { return _driver_index; }
- ///// SRV output /////
- void SRV_push_servos(void);
- ///// LED /////
- bool led_write(uint8_t led_index, uint8_t red, uint8_t green, uint8_t blue);
- // buzzer
- void set_buzzer_tone(float frequency, float duration_s);
- template <typename DataType_>
- class RegistryBinder {
- protected:
- typedef void (*Registry)(AP_UAVCAN* _ap_uavcan, uint8_t _node_id, const RegistryBinder& _cb);
- AP_UAVCAN* _uc;
- Registry _ffunc;
- public:
- RegistryBinder() :
- _uc(),
- _ffunc(),
- msg() {}
- RegistryBinder(AP_UAVCAN* uc, Registry ffunc) :
- _uc(uc),
- _ffunc(ffunc),
- msg(nullptr) {}
- void operator()(const uavcan::ReceivedDataStructure<DataType_>& _msg) {
- msg = &_msg;
- _ffunc(_uc, _msg.getSrcNodeID().get(), *this);
- }
- const uavcan::ReceivedDataStructure<DataType_> *msg;
- };
- private:
- class SystemClock: public uavcan::ISystemClock, uavcan::Noncopyable {
- public:
- SystemClock() = default;
- void adjustUtc(uavcan::UtcDuration adjustment) override {
- utc_adjustment_usec = adjustment.toUSec();
- }
- uavcan::MonotonicTime getMonotonic() const override {
- return uavcan::MonotonicTime::fromUSec(AP_HAL::micros64());
- }
- uavcan::UtcTime getUtc() const override {
- return uavcan::UtcTime::fromUSec(AP_HAL::micros64() + utc_adjustment_usec);
- }
- static SystemClock& instance() {
- static SystemClock inst;
- return inst;
- }
- private:
- int64_t utc_adjustment_usec;
- };
- // This will be needed to implement if UAVCAN is used with multithreading
- // Such cases will be firmware update, etc.
- class RaiiSynchronizer {};
- void loop(void);
- ///// SRV output /////
- void SRV_send_actuator();
- void SRV_send_esc();
- ///// LED /////
- void led_out_send();
- // buzzer
- void buzzer_send();
- // SafetyState
- void safety_state_send();
-
- uavcan::PoolAllocator<UAVCAN_NODE_POOL_SIZE, UAVCAN_NODE_POOL_BLOCK_SIZE, AP_UAVCAN::RaiiSynchronizer> _node_allocator;
- // UAVCAN parameters
- AP_Int8 _uavcan_node;
- AP_Int32 _servo_bm;
- AP_Int32 _esc_bm;
- AP_Int16 _servo_rate_hz;
- uavcan::Node<0> *_node;
- uint8_t _driver_index;
- char _thread_name[9];
- bool _initialized;
- #ifdef HAS_UAVCAN_SERVERS
- AP_UAVCAN_Servers _servers;
- #endif
- ///// SRV output /////
- struct {
- uint16_t pulse;
- bool esc_pending;
- bool servo_pending;
- } _SRV_conf[UAVCAN_SRV_NUMBER];
- uint8_t _SRV_armed;
- uint32_t _SRV_last_send_us;
- HAL_Semaphore SRV_sem;
- ///// LED /////
- struct led_device {
- uint8_t led_index;
- uint8_t red;
- uint8_t green;
- uint8_t blue;
- };
- struct {
- led_device devices[AP_UAVCAN_MAX_LED_DEVICES];
- uint8_t devices_count;
- uint64_t last_update;
- } _led_conf;
- HAL_Semaphore _led_out_sem;
- // buzzer
- struct {
- HAL_Semaphore sem;
- float frequency;
- float duration;
- uint8_t pending_mask; // mask of interfaces to send to
- } _buzzer;
- // safety status send state
- uint32_t _last_safety_state_ms;
- // safety button handling
- static void handle_button(AP_UAVCAN* ap_uavcan, uint8_t node_id, const ButtonCb &cb);
- };
- namespace AP {
- AP_UAVCAN &uavcan();
- };
- #endif /* AP_UAVCAN_H_ */
|