pub struct BATTERY_INFO_DATA {Show 20 fields
pub discharge_minimum_voltage: f32,
pub charging_minimum_voltage: f32,
pub resting_minimum_voltage: f32,
pub charging_maximum_voltage: f32,
pub charging_maximum_current: f32,
pub nominal_voltage: f32,
pub discharge_maximum_current: f32,
pub discharge_maximum_burst_current: f32,
pub design_capacity: f32,
pub full_charge_capacity: f32,
pub cycle_count: u16,
pub weight: u16,
pub id: u8,
pub battery_function: MavBatteryFunction,
pub mavtype: MavBatteryType,
pub state_of_health: u8,
pub cells_in_series: u8,
pub manufacture_date: CharArray<9>,
pub serial_number: CharArray<32>,
pub name: CharArray<50>,
}ardupilotmega only.Expand description
Battery information that is static, or requires infrequent update. This message should requested using MAV_CMD_REQUEST_MESSAGE and/or streamed at very low rate. BATTERY_STATUS_V2 is used for higher-rate battery status information.
ID: 372
Fields§
§discharge_minimum_voltage: f32Minimum per-cell voltage when discharging. 0: field not provided.
charging_minimum_voltage: f32Minimum per-cell voltage when charging. 0: field not provided.
resting_minimum_voltage: f32Minimum per-cell voltage when resting. 0: field not provided.
charging_maximum_voltage: f32Maximum per-cell voltage when charged. 0: field not provided.
charging_maximum_current: f32Maximum pack continuous charge current. 0: field not provided.
nominal_voltage: f32Battery nominal voltage. Used for conversion between Wh and Ah. 0: field not provided.
discharge_maximum_current: f32Maximum pack discharge current. 0: field not provided.
discharge_maximum_burst_current: f32Maximum pack discharge burst current. 0: field not provided.
design_capacity: f32Fully charged design capacity. 0: field not provided.
full_charge_capacity: f32Predicted battery capacity when fully charged (accounting for battery degradation). NAN: field not provided.
cycle_count: u16Lifetime count of the number of charge/discharge cycles (https://en.wikipedia.org/wiki/Charge_cycle). UINT16_MAX: field not provided.
weight: u16Battery weight. 0: field not provided.
id: u8Battery ID
battery_function: MavBatteryFunctionFunction of the battery.
mavtype: MavBatteryTypeType (chemistry) of the battery.
state_of_health: u8State of Health (SOH) estimate. Typically 100% at the time of manufacture and will decrease over time and use. -1: field not provided.
cells_in_series: u8Number of battery cells in series. 0: field not provided.
manufacture_date: CharArray<9>Manufacture date (DDMMYYYY) in ASCII characters, 0 terminated. All 0: field not provided.
serial_number: CharArray<32>Serial number in ASCII characters, 0 terminated. All 0: field not provided.
name: CharArray<50>Battery device name. Formatted as manufacturer name then product name, separated with an underscore (in ASCII characters), 0 terminated. All 0: field not provided.
Implementations§
Source§impl BATTERY_INFO_DATA
impl BATTERY_INFO_DATA
pub const ENCODED_LEN: usize = 140usize
pub const DEFAULT: Self
Trait Implementations§
Source§impl Clone for BATTERY_INFO_DATA
impl Clone for BATTERY_INFO_DATA
Source§fn clone(&self) -> BATTERY_INFO_DATA
fn clone(&self) -> BATTERY_INFO_DATA
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source. Read more