You can not select more than 25 topics Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.
 
 
 
 
 
 

89 lines
2.4 KiB

#pragma once
#include <AP_HAL/AP_HAL.h>
#include "AP_BattMonitor.h"
#include "AP_BattMonitor_Backend.h"
#define AP_BATTMONITOR_SERIAL_TIMEOUT_MICROS 5000000
#define BATTGO_CMD_REQUEST_INFO 0x40
#define BATTGO_CMD_REQUEST_ACTUAL_DATA 0x42
#define BATTGO_CMD_REQUEST_HISTORY 0x44
class AP_BattMonitor_Serial_BattGo : public AP_BattMonitor_Backend
{
public:
AP_BattMonitor_Serial_BattGo(AP_BattMonitor &mon,
AP_BattMonitor::BattMonitor_State &mon_state,
AP_BattMonitor_Params &params,
uint8_t serial_instance);
// enum BattMonitor_Serial_BattGo_Type
// {
// SERIAL_BATTGO_INFO = 0
// };
typedef enum
{
rsWaitSync,
rsWaitAddres,
rsWaitLength,
rsWaitData,
rsWaitChkSumL,
rsWaitChkSumH,
}eComunicainot_t;
// ~AP_BattMonitor_Serial_BattGo();
bool has_current() const override
{
return true;
}
void init() override;
/// Read the battery voltage and current. Should be called at 10hz
void read() override;
void request_info(void) override;
void request_history(void) override;
bool _has_cell_voltages;
bool has_cell_voltages() const override { return _has_cell_voltages; }
// static detection function
static bool detect(uint8_t serial_instance);
void update_battgo_param_mavlink(mavlink_channel_t chan,mavlink_battgo_info_t &mavlink_battgo_info_t);
void notice_to_send_battgo_param();
private:
AP_HAL::UARTDriver *uart = nullptr;
AP_BattMonitor::BattMonitor_State _interim_state; //TODO may need to fix
// char linebuf[10];
// uint8_t linebuf_len = 0;
const int Head1 = 0x55; //数据包帧头
uint8_t data_buf[76];
//uint8_t step;
//uint8_t addr;
uint8_t payload_length;
uint8_t payload_counter;
uint16_t check_sum;
uint16_t m_SyncByteCount = 0;
uint8_t m_eRxStatus = 0;
uint8_t m_u08RXCnt;
uint32_t last_rev_batt_time;
void requestBattData(uint8_t data);
bool get_reading();
//uint8_t crc_crc8(const uint8_t *p, uint8_t len);
//void gotoStepAddr(uint8_t &data);
//void setPayLoadData(uint8_t &usart_data);
bool parseBattGo();
void rxProcess(uint8_t data);
//void AP_BattMonitor_Serial_BattGo::doWithReadHeaderData(uint8_t &usart_data,uint8_t target_data,uint8_t step,uint8_t &payload_length,uint8_t &payload_count,uint8_t * data_buf,bool &is_read_header);
};