|
|
|
@ -37,6 +37,7 @@ void AP_BattMonitor_Serial_BattGo::init(void)
@@ -37,6 +37,7 @@ void AP_BattMonitor_Serial_BattGo::init(void)
|
|
|
|
|
{ |
|
|
|
|
requestBattData(BATTGO_CMD_REQUEST_ACTUAL_DATA); |
|
|
|
|
requestBattData(BATTGO_CMD_REQUEST_PARAM); |
|
|
|
|
requestBattData(BATTGO_CMD_REQUEST_HISTORY); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -300,6 +301,7 @@ void AP_BattMonitor_Serial_BattGo::setPayLoadData(uint8_t &usart_data)
@@ -300,6 +301,7 @@ void AP_BattMonitor_Serial_BattGo::setPayLoadData(uint8_t &usart_data)
|
|
|
|
|
|
|
|
|
|
// }
|
|
|
|
|
mavlink_battgo_info_t battgo_info_t; |
|
|
|
|
mavlink_battgo_history_t battgo_history_t ; |
|
|
|
|
bool AP_BattMonitor_Serial_BattGo::parseBattGo() |
|
|
|
|
{ |
|
|
|
|
|
|
|
|
@ -404,18 +406,23 @@ bool AP_BattMonitor_Serial_BattGo::parseBattGo()
@@ -404,18 +406,23 @@ bool AP_BattMonitor_Serial_BattGo::parseBattGo()
|
|
|
|
|
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); |
|
|
|
|
gcs().update_serial_battgo_info(&battgo_info_t); |
|
|
|
|
//requestBattData(BATTGO_CMD_REQUEST_HISTORY);
|
|
|
|
|
return true; |
|
|
|
|
} |
|
|
|
|
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]; |
|
|
|
|
battgo_history_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_history_t.battery_core_vol[i] = (data_buf[8+2*i+1]<<8)|data_buf[8+2*i]; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
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); |
|
|
|
|
battgo_history_t.Internal_resistance[i] = (data_buf[20+2*i+1]<<8)|data_buf[20+2*i]; |
|
|
|
|
} |
|
|
|
|
battgo_history_t.charge_state = data_buf[32]; |
|
|
|
|
gcs().update_serial_battgo_history(&battgo_history_t); |
|
|
|
|
return true; |
|
|
|
|
} |
|
|
|
|
return false; |
|
|
|
@ -447,5 +454,5 @@ void AP_BattMonitor_Serial_BattGo::read()
@@ -447,5 +454,5 @@ void AP_BattMonitor_Serial_BattGo::read()
|
|
|
|
|
|
|
|
|
|
void AP_BattMonitor_Serial_BattGo::notice_to_send_battgo_param() |
|
|
|
|
{ |
|
|
|
|
gcs().send_message(MSG_BATTGAO_PARAM); |
|
|
|
|
gcs().send_message(MSG_BATTGAO_INFO); |
|
|
|
|
} |
|
|
|
|