|
|
@ -2,7 +2,8 @@ |
|
|
|
#include <AP_HAL/AP_HAL.h> |
|
|
|
#include <AP_HAL/AP_HAL.h> |
|
|
|
#include "AP_BattMonitor_Serial_BattGo.h" |
|
|
|
#include "AP_BattMonitor_Serial_BattGo.h" |
|
|
|
#include <AP_SerialManager/AP_SerialManager.h> |
|
|
|
#include <AP_SerialManager/AP_SerialManager.h> |
|
|
|
|
|
|
|
#include <GCS_MAVLink/GCS_MAVLink.h> |
|
|
|
|
|
|
|
#include <GCS_MAVLink/GCS.h> |
|
|
|
#define MAXSONAR_SERIAL_LV_BAUD_RATE 115200 |
|
|
|
#define MAXSONAR_SERIAL_LV_BAUD_RATE 115200 |
|
|
|
extern const AP_HAL::HAL &hal; |
|
|
|
extern const AP_HAL::HAL &hal; |
|
|
|
|
|
|
|
|
|
|
@ -30,7 +31,8 @@ bool AP_BattMonitor_Serial_BattGo::detect(uint8_t serial_instance) //how to use |
|
|
|
return AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr; |
|
|
|
return AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
void AP_BattMonitor_Serial_BattGo::init(void ){ |
|
|
|
void AP_BattMonitor_Serial_BattGo::init(void) |
|
|
|
|
|
|
|
{ |
|
|
|
if (uart != nullptr) |
|
|
|
if (uart != nullptr) |
|
|
|
{ |
|
|
|
{ |
|
|
|
requestBattData(BATTGO_CMD_REQUEST_ACTUAL_DATA); |
|
|
|
requestBattData(BATTGO_CMD_REQUEST_ACTUAL_DATA); |
|
|
@ -238,7 +240,6 @@ void AP_BattMonitor_Serial_BattGo::gotoStepAddr( uint8_t &data) |
|
|
|
|
|
|
|
|
|
|
|
void AP_BattMonitor_Serial_BattGo::requestBattData(uint8_t data) |
|
|
|
void AP_BattMonitor_Serial_BattGo::requestBattData(uint8_t data) |
|
|
|
{ |
|
|
|
{ |
|
|
|
|
|
|
|
|
|
|
|
//发送data主要 0x40 0x42 0x44 地址0x21 及计算crc 均不会出现0x55,故不做0x55处理
|
|
|
|
//发送data主要 0x40 0x42 0x44 地址0x21 及计算crc 均不会出现0x55,故不做0x55处理
|
|
|
|
uint8_t send_data[6]; |
|
|
|
uint8_t send_data[6]; |
|
|
|
send_data[0] = 0x55; |
|
|
|
send_data[0] = 0x55; |
|
|
@ -248,7 +249,8 @@ void AP_BattMonitor_Serial_BattGo::requestBattData(uint8_t data) |
|
|
|
uint16_t crc = send_data[1] + send_data[2] + send_data[3]; |
|
|
|
uint16_t crc = send_data[1] + send_data[2] + send_data[3]; |
|
|
|
send_data[4] = crc & 0xff; |
|
|
|
send_data[4] = crc & 0xff; |
|
|
|
send_data[5] = crc >> 8 & 0xff; |
|
|
|
send_data[5] = crc >> 8 & 0xff; |
|
|
|
if (uart->txspace() > sizeof(send_data)) { |
|
|
|
if (uart->txspace() > sizeof(send_data)) |
|
|
|
|
|
|
|
{ |
|
|
|
uart->write(&send_data[0], sizeof(send_data)); |
|
|
|
uart->write(&send_data[0], sizeof(send_data)); |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
@ -297,9 +299,10 @@ void AP_BattMonitor_Serial_BattGo::setPayLoadData(uint8_t &usart_data) |
|
|
|
// }
|
|
|
|
// }
|
|
|
|
|
|
|
|
|
|
|
|
// }
|
|
|
|
// }
|
|
|
|
|
|
|
|
mavlink_battgo_info_t battgo_info_t; |
|
|
|
bool AP_BattMonitor_Serial_BattGo::parseBattGo() |
|
|
|
bool AP_BattMonitor_Serial_BattGo::parseBattGo() |
|
|
|
{ |
|
|
|
{ |
|
|
|
|
|
|
|
|
|
|
|
if (data_buf[0] == 0x43) |
|
|
|
if (data_buf[0] == 0x43) |
|
|
|
{ //电池实时数据
|
|
|
|
{ //电池实时数据
|
|
|
|
uint32_t tnow = AP_HAL::micros(); |
|
|
|
uint32_t tnow = AP_HAL::micros(); |
|
|
@ -333,10 +336,86 @@ bool AP_BattMonitor_Serial_BattGo::parseBattGo() |
|
|
|
else if (data_buf[0] == 0x41) |
|
|
|
else if (data_buf[0] == 0x41) |
|
|
|
{ |
|
|
|
{ |
|
|
|
//电池参数
|
|
|
|
//电池参数
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
battgo_info_t.channal_num = data_buf[1]; |
|
|
|
|
|
|
|
battgo_info_t.connect_status = data_buf[2]; |
|
|
|
|
|
|
|
battgo_info_t.sub_software_ver = data_buf[3]; |
|
|
|
|
|
|
|
battgo_info_t.main_software_ver = data_buf[4]; |
|
|
|
|
|
|
|
battgo_info_t.sub_hardware_ver = data_buf[5]; |
|
|
|
|
|
|
|
battgo_info_t.main_hardware_ver = data_buf[6]; |
|
|
|
|
|
|
|
for (int i = 0; i < 8; i++) |
|
|
|
|
|
|
|
{ |
|
|
|
|
|
|
|
battgo_info_t.equipment_id[i] = data_buf[7 + i]; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
for (int i = 0; i < 10; i++) |
|
|
|
|
|
|
|
{ |
|
|
|
|
|
|
|
battgo_info_t.slave_id[i] = data_buf[15 + i]; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
battgo_info_t.station_id = data_buf[25]; |
|
|
|
|
|
|
|
battgo_info_t.customer_id = data_buf[27] << 8 & data_buf[26]; |
|
|
|
|
|
|
|
battgo_info_t.battery_id = data_buf[31] << 24 & data_buf[30] << 16 & data_buf[29] << 8 & data_buf[28]; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
uint8_t sec = data_buf[32] & 0x1f; |
|
|
|
|
|
|
|
uint8_t min = (data_buf[32] & 0xe0 >> 5) | (data_buf[33] & 0x0F << 4); |
|
|
|
|
|
|
|
uint8_t hour = (data_buf[33] & 0xF0 << 4) | (data_buf[34] & 0x01 << 1); |
|
|
|
|
|
|
|
uint8_t day = data_buf[34] & 0x3e >> 1; |
|
|
|
|
|
|
|
uint8_t month = (data_buf[34] & 0xc0 >> 6) | (data_buf[35] & 0x03); |
|
|
|
|
|
|
|
uint16_t year = (data_buf[35] & 0xFC >> 2 )+ 2017; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
battgo_info_t.production_time_year = year; |
|
|
|
|
|
|
|
battgo_info_t.production_time_mon = month; |
|
|
|
|
|
|
|
battgo_info_t.production_time_mday = day; |
|
|
|
|
|
|
|
battgo_info_t.production_time_hour = hour; |
|
|
|
|
|
|
|
battgo_info_t.production_time_min = min; |
|
|
|
|
|
|
|
battgo_info_t.production_time_sec = sec; |
|
|
|
|
|
|
|
for (int i = 0; i < 16; i++) |
|
|
|
|
|
|
|
{ |
|
|
|
|
|
|
|
battgo_info_t.battery_brand[i] = data_buf[i]; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
battgo_info_t.type = data_buf[52]; |
|
|
|
|
|
|
|
battgo_info_t.core_amount = data_buf[53]; |
|
|
|
|
|
|
|
battgo_info_t.over_discharge_vol = (data_buf[55] << 8) | data_buf[54]; |
|
|
|
|
|
|
|
battgo_info_t.warning_vol = (data_buf[57] << 8) | data_buf[56]; |
|
|
|
|
|
|
|
battgo_info_t.storage_vol = (data_buf[59] << 8) | data_buf[58]; |
|
|
|
|
|
|
|
battgo_info_t.full_charge_vol = (data_buf[61] << 8) | data_buf[60]; |
|
|
|
|
|
|
|
battgo_info_t.battery_capacity = (data_buf[65] << 24) | (data_buf[64] << 16) | (data_buf[63] << 8) | data_buf[62]; |
|
|
|
|
|
|
|
battgo_info_t.charge_c_value = (data_buf[67] << 8) | data_buf[66]; |
|
|
|
|
|
|
|
battgo_info_t.discharge_c_value = (data_buf[69] << 8) | data_buf[68]; |
|
|
|
|
|
|
|
battgo_info_t.temp_using_min = data_buf[70]; |
|
|
|
|
|
|
|
battgo_info_t.temp_using_max = data_buf[71]; |
|
|
|
|
|
|
|
battgo_info_t.temp_store_nin = data_buf[72]; |
|
|
|
|
|
|
|
battgo_info_t.temp_store_max = data_buf[73]; |
|
|
|
|
|
|
|
battgo_info_t.enable_auto_store = data_buf[74]; |
|
|
|
|
|
|
|
for (int i = 0; i < 6; i++) |
|
|
|
|
|
|
|
{ |
|
|
|
|
|
|
|
battgo_info_t.battery_core_vol[i] = (data_buf[75 + 2 * i + 1] << 8) | (data_buf[75 + 2 * i]); |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
battgo_info_t.current_temp = data_buf[87]; |
|
|
|
|
|
|
|
battgo_info_t.actual_discharge_vol = (data_buf[91] << 24) | (data_buf[90] << 16) | (data_buf[89] << 8) |data_buf[88]; |
|
|
|
|
|
|
|
battgo_info_t.actual_charge_vol = (data_buf[95] << 24) | (data_buf[94] << 16) | (data_buf[93] << 8) |data_buf[92]; |
|
|
|
|
|
|
|
battgo_info_t.batt_cycle_times = (data_buf[97] << 8) |data_buf[96]; |
|
|
|
|
|
|
|
battgo_info_t.batt_abr_times = (data_buf[99] << 8) |data_buf[98]; |
|
|
|
|
|
|
|
battgo_info_t.temp_abr_times = (data_buf[101] << 8) |data_buf[100]; |
|
|
|
|
|
|
|
battgo_info_t.temp_abr_times = (data_buf[101] << 8) |data_buf[100]; |
|
|
|
|
|
|
|
battgo_info_t.over_vol_abr_times = (data_buf[103] << 8) |data_buf[102]; |
|
|
|
|
|
|
|
battgo_info_t.under_vol_abr_times = (data_buf[105] << 8) |data_buf[104]; |
|
|
|
|
|
|
|
battgo_info_t.soft_crash_times = data_buf[106]; |
|
|
|
|
|
|
|
battgo_info_t.current_charged_set = (data_buf[110] << 24) | (data_buf[109] << 16) | (data_buf[108] << 8) |data_buf[107]; |
|
|
|
|
|
|
|
battgo_info_t.vol_stored_set = (data_buf[112] << 8) |data_buf[111]; |
|
|
|
|
|
|
|
battgo_info_t.vol_stored_full_set = (data_buf[114] << 8) |data_buf[113]; |
|
|
|
|
|
|
|
battgo_info_t.self_discharge_times = (data_buf[115] << 8); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
requestBattData(BATTGO_CMD_REQUEST_HISTORY); |
|
|
|
return true; |
|
|
|
return true; |
|
|
|
} |
|
|
|
} |
|
|
|
else if (data_buf[0] == 0x45) //
|
|
|
|
else if (data_buf[0] == 0x45) //
|
|
|
|
{ |
|
|
|
{ |
|
|
|
|
|
|
|
battgo_info_t.last_charge_cap = (data_buf[7] << 24) | (data_buf[6] << 16) | (data_buf[5] << 8) |data_buf[4]; |
|
|
|
|
|
|
|
for(int i=0;i<6;i++){ |
|
|
|
|
|
|
|
battgo_info_t.Internal_resistance[i] = (data_buf[20+2*i+1]<<8)|data_buf[20+2*i]; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
battgo_info_t.charge_state = data_buf[32]; |
|
|
|
|
|
|
|
gcs().update_serial_battgo(&battgo_info_t); |
|
|
|
return true; |
|
|
|
return true; |
|
|
|
} |
|
|
|
} |
|
|
|
return false; |
|
|
|
return false; |
|
|
@ -349,7 +428,8 @@ void AP_BattMonitor_Serial_BattGo::read() |
|
|
|
{ |
|
|
|
{ |
|
|
|
uint32_t tnow = AP_HAL::micros(); |
|
|
|
uint32_t tnow = AP_HAL::micros(); |
|
|
|
// timeout after 5 seconds
|
|
|
|
// timeout after 5 seconds
|
|
|
|
if ((tnow - _interim_state.last_time_micros) > AP_BATTMONITOR_SERIAL_TIMEOUT_MICROS) { |
|
|
|
if ((tnow - _interim_state.last_time_micros) > AP_BATTMONITOR_SERIAL_TIMEOUT_MICROS) |
|
|
|
|
|
|
|
{ |
|
|
|
_interim_state.healthy = false; |
|
|
|
_interim_state.healthy = false; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
@ -364,3 +444,8 @@ void AP_BattMonitor_Serial_BattGo::read() |
|
|
|
_state.healthy = _interim_state.healthy; |
|
|
|
_state.healthy = _interim_state.healthy; |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
void AP_BattMonitor_Serial_BattGo::notice_to_send_battgo_param() |
|
|
|
|
|
|
|
{ |
|
|
|
|
|
|
|
gcs().send_message(MSG_BATTGAO_PARAM); |
|
|
|
|
|
|
|
} |
|
|
|