@ -12,13 +12,14 @@ AP_BattMonitor_Serial_BattGo::AP_BattMonitor_Serial_BattGo(AP_BattMonitor &mon,
@@ -12,13 +12,14 @@ AP_BattMonitor_Serial_BattGo::AP_BattMonitor_Serial_BattGo(AP_BattMonitor &mon,
AP_BattMonitor_Params & params ,
uint8_t serial_instance ) : AP_BattMonitor_Backend ( mon , mon_state , params )
{
const AP_SerialManager & serial_manager = AP : : serialmanager ( ) ;
uart = serial_manager . find_serial ( AP_SerialManager : : SerialProtocol_Battery , serial_instance ) ;
if ( uart ! = nullptr )
{
uart - > begin ( serial_manager . find_baudrate ( AP_SerialManager : : SerialProtocol_Battery , serial_instance ) ) ;
uart - > begin ( serial_manager . find_baudrate ( AP_SerialManager : : SerialProtocol_Battery , serial_instance ) ) ;
}
last_rev_batt_time = 0 ;
} ;
/*
@ -36,8 +37,8 @@ void AP_BattMonitor_Serial_BattGo::init(void)
@@ -36,8 +37,8 @@ void AP_BattMonitor_Serial_BattGo::init(void)
if ( uart ! = nullptr )
{
requestBattData ( BATTGO_CMD_REQUEST_ACTUAL_DATA ) ;
requestBattData ( BATTGO_CMD_REQUEST_INFO ) ;
requestBattData ( BATTGO_CMD_REQUEST_HISTORY ) ;
// requestBattData(BATTGO_CMD_REQUEST_INFO);
// requestBattData(BATTGO_CMD_REQUEST_HISTORY);
}
}
bool isparse = false ;
@ -51,8 +52,8 @@ bool AP_BattMonitor_Serial_BattGo::get_reading() //TODO need to Refactor
@@ -51,8 +52,8 @@ bool AP_BattMonitor_Serial_BattGo::get_reading() //TODO need to Refactor
int16_t numc ;
numc = uart - > available ( ) ;
uint8_t data ;
if ( numc = = 0 )
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " uasart num:%d " , numc ) ;
// if (numc == 0)
// gcs().send_text(MAV_SEVERITY_INFO, "uasart num:%d", numc);
isparse = false ;
for ( int16_t i = 0 ; i < numc ; i + + )
{
@ -95,7 +96,7 @@ mavlink_battgo_info_t battgo_info_t;
@@ -95,7 +96,7 @@ mavlink_battgo_info_t battgo_info_t;
mavlink_battgo_history_t battgo_history_t ;
bool AP_BattMonitor_Serial_BattGo : : parseBattGo ( )
{
uint8_t offset = 0 ;
if ( data_buf [ 0 ] = = 0x43 )
{ //电池实时数据
uint32_t tnow = AP_HAL : : micros ( ) ;
@ -119,17 +120,36 @@ bool AP_BattMonitor_Serial_BattGo::parseBattGo()
@@ -119,17 +120,36 @@ bool AP_BattMonitor_Serial_BattGo::parseBattGo()
_interim_state . consumed_mah + = mah ;
_interim_state . consumed_wh + = 0.001f * mah * _interim_state . voltage ;
}
battgo_history_t . batt_cycled_time = ( data_buf [ 25 ] < < 8 ) + data_buf [ 24 ] ;
battgo_history_t . batt_abnormal_time = ( data_buf [ 27 ] < < 8 ) + data_buf [ 26 ] ;
battgo_history_t . temp_abnormal_time = ( data_buf [ 29 ] < < 8 ) + data_buf [ 28 ] ;
battgo_history_t . over_vol_abnormal_time = ( data_buf [ 31 ] < < 8 ) + data_buf [ 30 ] ;
offset = 32 ;
battgo_history_t . under_vol_abnormal_time = ( data_buf [ offset + 1 ] < < 8 ) + data_buf [ offset ] ;
offset = offset + 2 ;
battgo_history_t . soft_crashes_time = data_buf [ offset ] ;
offset + + ;
battgo_history_t . charging_current_setted = ( data_buf [ offset + 3 ] + ( data_buf [ offset + 2 ] < < 8 ) + ( data_buf [ offset + 1 ] < < 16 ) + ( data_buf [ offset ] < < 24 ) ) ;
offset = offset + 4 ;
battgo_history_t . storage_vol_setted = ( data_buf [ offset + 1 ] < < 8 ) + data_buf [ offset ] ;
offset + = 2 ;
battgo_history_t . charging_full_vol_setted = ( data_buf [ offset + 1 ] < < 8 ) + data_buf [ offset ] ;
offset + = 2 ;
battgo_history_t . self_discharge_times_setted = data_buf [ offset ] ;
//battgo_history_t.set
// record time
_interim_state . last_time_micros = tnow ;
_interim_state . healthy = true ;
return true ;
}
else if ( data_buf [ 0 ] = = 0x41 )
{
//电池参数
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " into battgo 0x41 battgo info " ) ;
//gcs().send_text(MAV_SEVERITY_INFO, "into battgo 0x41 battgo info");
battgo_info_t . channal_num = data_buf [ 1 ] ;
battgo_info_t . connect_status = data_buf [ 2 ] ;
battgo_info_t . sub_hardware_ver = data_buf [ 3 ] ;
@ -185,7 +205,7 @@ bool AP_BattMonitor_Serial_BattGo::parseBattGo()
@@ -185,7 +205,7 @@ bool AP_BattMonitor_Serial_BattGo::parseBattGo()
}
else if ( data_buf [ 0 ] = = 0x45 ) //
{
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " into battgo 0x45 battgo history " ) ;
// gcs().send_text(MAV_SEVERITY_INFO, "into battgo 0x45 battgo history");
battgo_history_t . channal_num = data_buf [ 1 ] ;
battgo_history_t . channal_num = data_buf [ 2 ] ;
battgo_history_t . last_charge_cap = ( data_buf [ 6 ] < < 24 ) | ( data_buf [ 5 ] < < 16 ) | ( data_buf [ 4 ] < < 8 ) | data_buf [ 3 ] ;
@ -209,20 +229,19 @@ bool AP_BattMonitor_Serial_BattGo::parseBattGo()
@@ -209,20 +229,19 @@ bool AP_BattMonitor_Serial_BattGo::parseBattGo()
void AP_BattMonitor_Serial_BattGo : : read ( )
{
requestBattData ( 0x42 ) ;
requestBattData ( BATTGO_CMD_REQUEST_ACTUAL_DATA ) ;
uint32_t tnow = AP_HAL : : micros ( ) ;
if ( get_reading ( ) )
{
if ( parseBattGo ( ) )
{
uint32_t tnow = AP_HAL : : micros ( ) ;
{
last_rev_batt_time = tnow ;
// timeout after 5 seconds
if ( ( tnow - _interim_state . last_time_micros ) > AP_BATTMONITOR_SERIAL_TIMEOUT_MICROS )
{
_interim_state . healthy = false ;
}
// Copy over relevant states over to main state
// WITH_SEMAPHORE(_sem_battmon);
@ -237,7 +256,17 @@ void AP_BattMonitor_Serial_BattGo::read()
@@ -237,7 +256,17 @@ void AP_BattMonitor_Serial_BattGo::read()
_state . temperature_time = _interim_state . temperature_time ;
//...
_state . healthy = _interim_state . healthy ;
} else {
if ( tnow - last_rev_batt_time > 5000000 ) {
_interim_state . healthy = false ;
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " BATT_ERR:已经%d秒没有接收到智能电池 的串口数据! " , ( tnow - last_rev_batt_time ) / 1000000 ) ;
}
}
} else {
if ( tnow - last_rev_batt_time > 5000000 ) {
_interim_state . healthy = false ;
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " BATT_ERR:已经%d秒没有接收到智能电池 的串口数据! " , ( tnow - last_rev_batt_time ) / 1000000 ) ;
}
}
}