forked from Archive/PX4-Autopilot
Track raw battery voltage and filtered battery voltage separately. Estimate remaining battery as min(voltage_estimate, discharged_estimate). Battery voltage LPF time increased.
This commit is contained in:
parent
e8487b7498
commit
714f5ea634
|
@ -107,14 +107,9 @@ static const int ERROR = -1;
|
|||
|
||||
extern struct system_load_s system_load;
|
||||
|
||||
#define LOW_VOLTAGE_BATTERY_HYSTERESIS_TIME_MS 1000.0f
|
||||
#define CRITICAL_VOLTAGE_BATTERY_HYSTERESIS_TIME_MS 100.0f
|
||||
|
||||
/* Decouple update interval and hysteris counters, all depends on intervals */
|
||||
#define COMMANDER_MONITORING_INTERVAL 50000
|
||||
#define COMMANDER_MONITORING_LOOPSPERMSEC (1/(COMMANDER_MONITORING_INTERVAL/1000.0f))
|
||||
#define LOW_VOLTAGE_BATTERY_COUNTER_LIMIT (LOW_VOLTAGE_BATTERY_HYSTERESIS_TIME_MS*COMMANDER_MONITORING_LOOPSPERMSEC)
|
||||
#define CRITICAL_VOLTAGE_BATTERY_COUNTER_LIMIT (CRITICAL_VOLTAGE_BATTERY_HYSTERESIS_TIME_MS*COMMANDER_MONITORING_LOOPSPERMSEC)
|
||||
|
||||
#define MAVLINK_OPEN_INTERVAL 50000
|
||||
|
||||
|
@ -666,8 +661,6 @@ int commander_thread_main(int argc, char *argv[])
|
|||
|
||||
/* Start monitoring loop */
|
||||
unsigned counter = 0;
|
||||
unsigned low_voltage_counter = 0;
|
||||
unsigned critical_voltage_counter = 0;
|
||||
unsigned stick_off_counter = 0;
|
||||
unsigned stick_on_counter = 0;
|
||||
|
||||
|
@ -745,7 +738,6 @@ int commander_thread_main(int argc, char *argv[])
|
|||
int battery_sub = orb_subscribe(ORB_ID(battery_status));
|
||||
struct battery_status_s battery;
|
||||
memset(&battery, 0, sizeof(battery));
|
||||
battery.voltage_v = 0.0f;
|
||||
|
||||
/* Subscribe to subsystem info topic */
|
||||
int subsys_sub = orb_subscribe(ORB_ID(subsystem_info));
|
||||
|
@ -890,15 +882,12 @@ int commander_thread_main(int argc, char *argv[])
|
|||
|
||||
if (updated) {
|
||||
orb_copy(ORB_ID(battery_status), battery_sub, &battery);
|
||||
|
||||
// warnx("bat v: %2.2f", battery.voltage_v);
|
||||
|
||||
/* only consider battery voltage if system has been running 2s and battery voltage is higher than 4V */
|
||||
if (hrt_absolute_time() > start_time + 2000000 && battery.voltage_v > 4.0f) {
|
||||
status.battery_voltage = battery.voltage_v;
|
||||
/* only consider battery voltage if system has been running 2s and battery voltage is valid */
|
||||
if (hrt_absolute_time() > start_time + 2000000 && battery.voltage_filtered_v > 0.0f) {
|
||||
status.battery_voltage = battery.voltage_filtered_v;
|
||||
status.battery_current = battery.current_a;
|
||||
status.condition_battery_voltage_valid = true;
|
||||
status.battery_remaining = battery_remaining_estimate_voltage(battery.voltage_v, battery.discharged_mah);
|
||||
status.battery_remaining = battery_remaining_estimate_voltage(battery.voltage_filtered_v, battery.discharged_mah);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -951,46 +940,29 @@ int commander_thread_main(int argc, char *argv[])
|
|||
//on_usb_power = (stat("/dev/ttyACM0", &statbuf) == 0);
|
||||
}
|
||||
|
||||
// XXX remove later
|
||||
//warnx("bat remaining: %2.2f", status.battery_remaining);
|
||||
|
||||
/* if battery voltage is getting lower, warn using buzzer, etc. */
|
||||
if (status.condition_battery_voltage_valid && status.battery_remaining < 0.25f && !low_battery_voltage_actions_done) {
|
||||
//TODO: add filter, or call emergency after n measurements < VOLTAGE_BATTERY_MINIMAL_MILLIVOLTS
|
||||
if (low_voltage_counter > LOW_VOLTAGE_BATTERY_COUNTER_LIMIT) {
|
||||
low_battery_voltage_actions_done = true;
|
||||
mavlink_log_critical(mavlink_fd, "#audio: WARNING: LOW BATTERY");
|
||||
status.battery_warning = VEHICLE_BATTERY_WARNING_LOW;
|
||||
status_changed = true;
|
||||
battery_tune_played = false;
|
||||
}
|
||||
|
||||
low_voltage_counter++;
|
||||
low_battery_voltage_actions_done = true;
|
||||
mavlink_log_critical(mavlink_fd, "#audio: WARNING: LOW BATTERY");
|
||||
status.battery_warning = VEHICLE_BATTERY_WARNING_LOW;
|
||||
status_changed = true;
|
||||
battery_tune_played = false;
|
||||
|
||||
} else if (status.condition_battery_voltage_valid && status.battery_remaining < 0.1f && !critical_battery_voltage_actions_done && low_battery_voltage_actions_done) {
|
||||
/* critical battery voltage, this is rather an emergency, change state machine */
|
||||
if (critical_voltage_counter > CRITICAL_VOLTAGE_BATTERY_COUNTER_LIMIT) {
|
||||
critical_battery_voltage_actions_done = true;
|
||||
mavlink_log_critical(mavlink_fd, "#audio: EMERGENCY: CRITICAL BATTERY");
|
||||
status.battery_warning = VEHICLE_BATTERY_WARNING_CRITICAL;
|
||||
battery_tune_played = false;
|
||||
critical_battery_voltage_actions_done = true;
|
||||
mavlink_log_critical(mavlink_fd, "#audio: EMERGENCY: CRITICAL BATTERY");
|
||||
status.battery_warning = VEHICLE_BATTERY_WARNING_CRITICAL;
|
||||
battery_tune_played = false;
|
||||
|
||||
if (armed.armed) {
|
||||
arming_state_transition(&status, &safety, &control_mode, ARMING_STATE_ARMED_ERROR, &armed);
|
||||
if (armed.armed) {
|
||||
arming_state_transition(&status, &safety, &control_mode, ARMING_STATE_ARMED_ERROR, &armed);
|
||||
|
||||
} else {
|
||||
arming_state_transition(&status, &safety, &control_mode, ARMING_STATE_STANDBY_ERROR, &armed);
|
||||
}
|
||||
|
||||
status_changed = true;
|
||||
} else {
|
||||
arming_state_transition(&status, &safety, &control_mode, ARMING_STATE_STANDBY_ERROR, &armed);
|
||||
}
|
||||
|
||||
critical_voltage_counter++;
|
||||
|
||||
} else {
|
||||
|
||||
low_voltage_counter = 0;
|
||||
critical_voltage_counter = 0;
|
||||
status_changed = true;
|
||||
}
|
||||
|
||||
/* End battery voltage check */
|
||||
|
|
|
@ -44,6 +44,7 @@
|
|||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <fcntl.h>
|
||||
#include <math.h>
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/vehicle_status.h>
|
||||
|
@ -282,12 +283,15 @@ float battery_remaining_estimate_voltage(float voltage, float discharged)
|
|||
|
||||
counter++;
|
||||
|
||||
/* remaining charge estimate based on voltage */
|
||||
float remaining_voltage = (voltage - bat_n_cells * bat_v_empty) / (bat_n_cells * (bat_v_full - bat_v_empty));
|
||||
|
||||
if (bat_capacity > 0.0f) {
|
||||
/* if battery capacity is known, use it to estimate remaining charge */
|
||||
ret = 1.0f - discharged / bat_capacity;
|
||||
/* if battery capacity is known, use discharged current for estimate, but don't show more than voltage estimate */
|
||||
ret = fminf(remaining_voltage, 1.0f - discharged / bat_capacity);
|
||||
} else {
|
||||
/* else use voltage */
|
||||
ret = (voltage - bat_n_cells * bat_v_empty) / (bat_n_cells * (bat_v_full - bat_v_empty));
|
||||
ret = remaining_voltage;
|
||||
}
|
||||
|
||||
/* limit to sane values */
|
||||
|
|
|
@ -1264,6 +1264,7 @@ int sdlog2_thread_main(int argc, char *argv[])
|
|||
orb_copy(ORB_ID(battery_status), subs.battery_sub, &buf.battery);
|
||||
log_msg.msg_type = LOG_BATT_MSG;
|
||||
log_msg.body.log_BATT.voltage = buf.battery.voltage_v;
|
||||
log_msg.body.log_BATT.voltage_filtered = buf.battery.voltage_filtered_v;
|
||||
log_msg.body.log_BATT.current = buf.battery.current_a;
|
||||
log_msg.body.log_BATT.discharged = buf.battery.discharged_mah;
|
||||
LOGBUFFER_WRITE_AND_COUNT(BATT);
|
||||
|
|
|
@ -249,6 +249,7 @@ struct log_GVSP_s {
|
|||
#define LOG_BATT_MSG 20
|
||||
struct log_BATT_s {
|
||||
float voltage;
|
||||
float voltage_filtered;
|
||||
float current;
|
||||
float discharged;
|
||||
};
|
||||
|
@ -296,7 +297,7 @@ static const struct log_format_s log_formats[] = {
|
|||
LOG_FORMAT(GPSP, "BLLfffbBffff", "AltRel,Lat,Lon,Alt,Yaw,LoiterR,LoiterDir,NavCmd,P1,P2,P3,P4"),
|
||||
LOG_FORMAT(ESC, "HBBBHHHHHHfH", "Counter,NumESC,Conn,N,Ver,Adr,Volt,Amp,RPM,Temp,SetP,SetPRAW"),
|
||||
LOG_FORMAT(GVSP, "fff", "VX,VY,VZ"),
|
||||
LOG_FORMAT(BATT, "fff", "V,C,Discharged"),
|
||||
LOG_FORMAT(BATT, "ffff", "V,VFilt,C,Discharged"),
|
||||
/* system-level messages, ID >= 0x80 */
|
||||
// FMT: don't write format of format message, it's useless
|
||||
LOG_FORMAT(TIME, "Q", "StartTime"),
|
||||
|
|
|
@ -125,9 +125,8 @@
|
|||
#define ADC_AIRSPEED_VOLTAGE_CHANNEL 15
|
||||
#endif
|
||||
|
||||
#define BAT_VOL_INITIAL 0.f
|
||||
#define BAT_VOL_LOWPASS 0.01f
|
||||
#define VOLTAGE_BATTERY_IGNORE_THRESHOLD_VOLTS 3.5f
|
||||
#define BATT_V_LOWPASS 0.001f
|
||||
#define BATT_V_IGNORE_THRESHOLD 3.5f
|
||||
|
||||
/**
|
||||
* HACK - true temperature is much less than indicated temperature in baro,
|
||||
|
@ -1173,32 +1172,40 @@ Sensors::adc_poll(struct sensor_combined_s &raw)
|
|||
/* Voltage in volts */
|
||||
float voltage = (buf_adc[i].am_data * _parameters.battery_voltage_scaling);
|
||||
|
||||
if (voltage > VOLTAGE_BATTERY_IGNORE_THRESHOLD_VOLTS) {
|
||||
if (voltage > BATT_V_IGNORE_THRESHOLD) {
|
||||
_battery_status.voltage_v = voltage;
|
||||
/* one-time initialization of low-pass value to avoid long init delays */
|
||||
if (_battery_status.voltage_v < VOLTAGE_BATTERY_IGNORE_THRESHOLD_VOLTS) {
|
||||
_battery_status.voltage_v = voltage;
|
||||
if (_battery_status.voltage_filtered_v < BATT_V_IGNORE_THRESHOLD) {
|
||||
_battery_status.voltage_filtered_v = voltage;
|
||||
}
|
||||
|
||||
_battery_status.timestamp = t;
|
||||
_battery_status.voltage_v += (voltage - _battery_status.voltage_v) * BAT_VOL_LOWPASS;
|
||||
_battery_status.voltage_filtered_v += (voltage - _battery_status.voltage_filtered_v) * BATT_V_LOWPASS;
|
||||
|
||||
} else {
|
||||
/* mark status as invalid */
|
||||
_battery_status.timestamp = 0;
|
||||
_battery_status.voltage_v = -1.0f;
|
||||
_battery_status.voltage_filtered_v = -1.0f;
|
||||
}
|
||||
|
||||
} else if (ADC_BATTERY_CURRENT_CHANNEL == buf_adc[i].am_channel) {
|
||||
/* handle current only if voltage is valid */
|
||||
if (_battery_status.timestamp != 0) {
|
||||
if (_battery_status.voltage_v > 0.0f) {
|
||||
float current = (buf_adc[i].am_data * _parameters.battery_current_scaling);
|
||||
_battery_status.timestamp = t;
|
||||
_battery_status.current_a = current;
|
||||
if (_battery_current_timestamp != 0) {
|
||||
_battery_discharged += current * (t - _battery_current_timestamp);
|
||||
_battery_status.discharged_mah = ((float) _battery_discharged) / 3600000.0f;
|
||||
/* check measured current value */
|
||||
if (current >= 0.0f) {
|
||||
_battery_status.timestamp = t;
|
||||
_battery_status.current_a = current;
|
||||
if (_battery_current_timestamp != 0) {
|
||||
/* initialize discharged value */
|
||||
if (_battery_status.discharged_mah < 0.0f)
|
||||
_battery_status.discharged_mah = 0.0f;
|
||||
_battery_discharged += current * (t - _battery_current_timestamp);
|
||||
_battery_status.discharged_mah = ((float) _battery_discharged) / 3600000.0f;
|
||||
}
|
||||
}
|
||||
_battery_current_timestamp = t;
|
||||
}
|
||||
_battery_current_timestamp = t;
|
||||
|
||||
} else if (ADC_AIRSPEED_VOLTAGE_CHANNEL == buf_adc[i].am_channel) {
|
||||
|
||||
|
@ -1229,7 +1236,7 @@ Sensors::adc_poll(struct sensor_combined_s &raw)
|
|||
}
|
||||
}
|
||||
_last_adc = t;
|
||||
if (_battery_status.timestamp != 0) {
|
||||
if (_battery_status.voltage_v > 0.0f) {
|
||||
/* announce the battery status if needed, just publish else */
|
||||
if (_battery_pub > 0) {
|
||||
orb_publish(ORB_ID(battery_status), _battery_pub, &_battery_status);
|
||||
|
@ -1512,7 +1519,10 @@ Sensors::task_main()
|
|||
raw.adc_voltage_v[3] = 0.0f;
|
||||
|
||||
memset(&_battery_status, 0, sizeof(_battery_status));
|
||||
_battery_status.voltage_v = BAT_VOL_INITIAL;
|
||||
_battery_status.voltage_v = 0.0f;
|
||||
_battery_status.voltage_filtered_v = 0.0f;
|
||||
_battery_status.current_a = -1.0f;
|
||||
_battery_status.discharged_mah = -1.0f;
|
||||
|
||||
/* get a set of initial values */
|
||||
accel_poll(raw);
|
||||
|
|
|
@ -53,7 +53,8 @@
|
|||
*/
|
||||
struct battery_status_s {
|
||||
uint64_t timestamp; /**< microseconds since system boot, needed to integrate */
|
||||
float voltage_v; /**< Battery voltage in volts, filtered */
|
||||
float voltage_v; /**< Battery voltage in volts, 0 if unknown */
|
||||
float voltage_filtered_v; /**< Battery voltage in volts, filtered, 0 if unknown */
|
||||
float current_a; /**< Battery current in amperes, -1 if unknown */
|
||||
float discharged_mah; /**< Discharged amount in mAh, -1 if unknown */
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue