Updated batt_smbus. Expanded battery_status.msg. Fixed mavlink_messages.cpp temperature. (#8991)

* Updated and expanded batt_smbus to work with bq40z50-R2. Expanded battery_status.msg. Fixed mavlink_messages.cpp temperature, added commented out expanded battery_status.msg parameters for future mavlink expansion.

* Changed errx to PX4_ERR

* Added PX4_ERR returns
This commit is contained in:
AlexKlimaj
2018-03-06 02:42:20 -07:00
committed by Lorenz Meier
parent bf097d7fa4
commit 83d01a7c76
3 changed files with 180 additions and 273 deletions
+8
View File
@@ -2,13 +2,21 @@ float32 voltage_v # Battery voltage in volts, 0 if unknown
float32 voltage_filtered_v # Battery voltage in volts, filtered, 0 if unknown
float32 current_a # Battery current in amperes, -1 if unknown
float32 current_filtered_a # Battery current in amperes, filtered, 0 if unknown
float32 average_current_a # Battery current average in amperes, -1 if unknown
float32 discharged_mah # Discharged amount in mAh, -1 if unknown
float32 remaining # From 1 to 0, -1 if unknown
float32 scale # Power scaling factor, >= 1, or -1 if unknown
float32 temperature # temperature of the battery
int32 cell_count # Number of cells
bool connected # Whether or not a battery is connected, based on a voltage threshold
bool system_source # Whether or not a this battery is the active power source for VDD_5V_IN
uint8 priority # Zerro based priority is the connection on the Power Controller V1..Vn AKA BrickN-1
uint16 capacity # actual capacity of the battery
uint16 cycle_count # number of discharge cycles the battery has experienced
uint16 run_time_to_empty # predicted remaining battery capacity based on the present rate of discharge in min
uint16 average_time_to_empty # predicted remaining battery capacity based on the average rate of discharge in min
uint16 serial_number # serial number of the battery pack
bool is_powering_off # Power off event imminent indication, false if unknown
File diff suppressed because it is too large Load Diff
+7 -1
View File
@@ -573,7 +573,13 @@ protected:
bat_msg.energy_consumed = -1;
bat_msg.current_battery = (battery_status.connected) ? battery_status.current_filtered_a * 100 : -1;
bat_msg.battery_remaining = (battery_status.connected) ? ceilf(battery_status.remaining * 100.0f) : -1;
bat_msg.temperature = INT16_MAX;
bat_msg.temperature = (battery_status.connected) ? (int16_t)battery_status.temperature : INT16_MAX;
//bat_msg.average_current_battery = (battery_status.connected) ? battery_status.average_current_a * 100.0f : -1;
//bat_msg.serial_number = (battery_status.connected) ? battery_status.serial_number : 0;
//bat_msg.capacity = (battery_status.connected) ? battery_status.capacity : 0;
//bat_msg.cycle_count = (battery_status.connected) ? battery_status.cycle_count : UINT16_MAX;
//bat_msg.run_time_to_empty = (battery_status.connected) ? battery_status.run_time_to_empty * 60 : 0;
//bat_msg.average_time_to_empty = (battery_status.connected) ? battery_status.average_time_to_empty * 60 : 0;
for (unsigned int i = 0; i < (sizeof(bat_msg.voltages) / sizeof(bat_msg.voltages[0])); i++) {
if ((int)i < battery_status.cell_count && battery_status.connected) {