Sub: Move battery logging to AP_BattMonitor
This commit is contained in:
parent
2e9e91b3a3
commit
02a660e0ce
@ -12,15 +12,6 @@ void Sub::do_erase_logs(void)
|
|||||||
gcs().send_text(MAV_SEVERITY_INFO, "Log erase complete");
|
gcs().send_text(MAV_SEVERITY_INFO, "Log erase complete");
|
||||||
}
|
}
|
||||||
|
|
||||||
// Write a Current data packet
|
|
||||||
void Sub::Log_Write_Current()
|
|
||||||
{
|
|
||||||
DataFlash.Log_Write_Current(battery);
|
|
||||||
|
|
||||||
// also write power status
|
|
||||||
DataFlash.Log_Write_Power();
|
|
||||||
}
|
|
||||||
|
|
||||||
struct PACKED log_Optflow {
|
struct PACKED log_Optflow {
|
||||||
LOG_PACKET_HEADER;
|
LOG_PACKET_HEADER;
|
||||||
uint64_t time_us;
|
uint64_t time_us;
|
||||||
@ -472,7 +463,6 @@ void Sub::log_init(void)
|
|||||||
#else // LOGGING_ENABLED
|
#else // LOGGING_ENABLED
|
||||||
|
|
||||||
void Sub::do_erase_logs(void) {}
|
void Sub::do_erase_logs(void) {}
|
||||||
void Sub::Log_Write_Current() {}
|
|
||||||
void Sub::Log_Write_Nav_Tuning() {}
|
void Sub::Log_Write_Nav_Tuning() {}
|
||||||
void Sub::Log_Write_Control_Tuning() {}
|
void Sub::Log_Write_Control_Tuning() {}
|
||||||
void Sub::Log_Write_Performance() {}
|
void Sub::Log_Write_Performance() {}
|
||||||
|
@ -328,7 +328,7 @@ private:
|
|||||||
uint32_t nav_delay_time_start;
|
uint32_t nav_delay_time_start;
|
||||||
|
|
||||||
// Battery Sensors
|
// Battery Sensors
|
||||||
AP_BattMonitor battery;
|
AP_BattMonitor battery{MASK_LOG_CURRENT};
|
||||||
|
|
||||||
AP_Arming_Sub arming{ahrs, barometer, compass, battery};
|
AP_Arming_Sub arming{ahrs, barometer, compass, battery};
|
||||||
|
|
||||||
@ -507,7 +507,6 @@ private:
|
|||||||
void gcs_data_stream_send(void);
|
void gcs_data_stream_send(void);
|
||||||
void gcs_check_input(void);
|
void gcs_check_input(void);
|
||||||
void do_erase_logs(void);
|
void do_erase_logs(void);
|
||||||
void Log_Write_Current();
|
|
||||||
void Log_Write_Optflow();
|
void Log_Write_Optflow();
|
||||||
void Log_Write_Nav_Tuning();
|
void Log_Write_Nav_Tuning();
|
||||||
void Log_Write_Control_Tuning();
|
void Log_Write_Control_Tuning();
|
||||||
|
@ -174,11 +174,6 @@ void Sub::read_battery(void)
|
|||||||
{
|
{
|
||||||
battery.read();
|
battery.read();
|
||||||
|
|
||||||
// update compass with current value
|
|
||||||
if (battery.has_current()) {
|
|
||||||
compass.set_current(battery.current_amps());
|
|
||||||
}
|
|
||||||
|
|
||||||
// update motors with voltage and current
|
// update motors with voltage and current
|
||||||
if (battery.get_type() != AP_BattMonitor_Params::BattMonitor_TYPE_NONE) {
|
if (battery.get_type() != AP_BattMonitor_Params::BattMonitor_TYPE_NONE) {
|
||||||
motors.set_voltage(battery.voltage());
|
motors.set_voltage(battery.voltage());
|
||||||
@ -186,14 +181,10 @@ void Sub::read_battery(void)
|
|||||||
|
|
||||||
if (battery.has_current()) {
|
if (battery.has_current()) {
|
||||||
motors.set_current(battery.current_amps());
|
motors.set_current(battery.current_amps());
|
||||||
|
compass.set_current(battery.current_amps());
|
||||||
}
|
}
|
||||||
|
|
||||||
failsafe_battery_check();
|
failsafe_battery_check();
|
||||||
|
|
||||||
// log battery info to the dataflash
|
|
||||||
if (should_log(MASK_LOG_CURRENT)) {
|
|
||||||
Log_Write_Current();
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void Sub::compass_cal_update()
|
void Sub::compass_cal_update()
|
||||||
|
Loading…
Reference in New Issue
Block a user