Copter: Move logging battery logging code to AP_BattMonitor
This commit is contained in:
parent
43972f8e56
commit
69da4041ac
@ -388,7 +388,7 @@ private:
|
|||||||
int32_t initial_armed_bearing;
|
int32_t initial_armed_bearing;
|
||||||
|
|
||||||
// Battery Sensors
|
// Battery Sensors
|
||||||
AP_BattMonitor battery;
|
AP_BattMonitor battery{MASK_LOG_CURRENT};
|
||||||
|
|
||||||
#if FRSKY_TELEM_ENABLED == ENABLED
|
#if FRSKY_TELEM_ENABLED == ENABLED
|
||||||
// FrSky telemetry support
|
// FrSky telemetry support
|
||||||
@ -756,7 +756,6 @@ private:
|
|||||||
void update_notify();
|
void update_notify();
|
||||||
|
|
||||||
// Log.cpp
|
// Log.cpp
|
||||||
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();
|
||||||
|
@ -59,15 +59,6 @@ void Copter::ModeAutoTune::Log_Write_AutoTuneDetails(float angle_cd, float rate_
|
|||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Write a Current data packet
|
|
||||||
void Copter::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;
|
||||||
@ -700,7 +691,6 @@ void Copter::Log_Write_AutoTune(uint8_t axis, uint8_t tune_step, float meas_targ
|
|||||||
float meas_min, float meas_max, float new_gain_rp, \
|
float meas_min, float meas_max, float new_gain_rp, \
|
||||||
float new_gain_rd, float new_gain_sp, float new_ddt) {}
|
float new_gain_rd, float new_gain_sp, float new_ddt) {}
|
||||||
void Copter::Log_Write_AutoTuneDetails(float angle_cd, float rate_cds) {}
|
void Copter::Log_Write_AutoTuneDetails(float angle_cd, float rate_cds) {}
|
||||||
void Copter::Log_Write_Current() {}
|
|
||||||
void Copter::Log_Write_Nav_Tuning() {}
|
void Copter::Log_Write_Nav_Tuning() {}
|
||||||
void Copter::Log_Write_Control_Tuning() {}
|
void Copter::Log_Write_Control_Tuning() {}
|
||||||
void Copter::Log_Write_Performance() {}
|
void Copter::Log_Write_Performance() {}
|
||||||
|
@ -185,17 +185,14 @@ void Copter::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());
|
||||||
AP_Notify::flags.battery_voltage = battery.voltage();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
if (battery.has_current()) {
|
if (battery.has_current()) {
|
||||||
|
compass.set_current(battery.current_amps());
|
||||||
|
|
||||||
motors->set_current(battery.current_amps());
|
motors->set_current(battery.current_amps());
|
||||||
motors->set_resistance(battery.get_resistance());
|
motors->set_resistance(battery.get_resistance());
|
||||||
motors->set_voltage_resting_estimate(battery.voltage_resting_estimate());
|
motors->set_voltage_resting_estimate(battery.voltage_resting_estimate());
|
||||||
@ -206,11 +203,6 @@ void Copter::read_battery(void)
|
|||||||
if (!ap.usb_connected && !failsafe.battery && battery.exhausted(g.fs_batt_voltage, g.fs_batt_mah)) {
|
if (!ap.usb_connected && !failsafe.battery && battery.exhausted(g.fs_batt_voltage, g.fs_batt_mah)) {
|
||||||
failsafe_battery_event();
|
failsafe_battery_event();
|
||||||
}
|
}
|
||||||
|
|
||||||
// log battery info to the dataflash
|
|
||||||
if (should_log(MASK_LOG_CURRENT)) {
|
|
||||||
Log_Write_Current();
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// read the receiver RSSI as an 8 bit number for MAVLink
|
// read the receiver RSSI as an 8 bit number for MAVLink
|
||||||
|
Loading…
Reference in New Issue
Block a user