You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
Copy file name to clipboardExpand all lines: protos/telemetry/telemetry.proto
+6-3Lines changed: 6 additions & 3 deletions
Original file line number
Diff line number
Diff line change
@@ -593,9 +593,12 @@ enum FixType {
593
593
594
594
// Battery type.
595
595
messageBattery {
596
-
uint32id=3 [(mavsdk.options.default_value)="0"]; // Battery ID, for systems with multiple batteries
597
-
floatvoltage_v=1 [(mavsdk.options.default_value)="NaN"]; // Voltage in volts
598
-
floatremaining_percent=2 [(mavsdk.options.default_value)="NaN"]; // Estimated battery remaining (range: 0.0 to 1.0)
596
+
uint32id=1 [(mavsdk.options.default_value)="0"]; // Battery ID, for systems with multiple batteries
597
+
floattemperature_degc=2 [(mavsdk.options.default_value)="NaN"]; // Temperature of the battery in degrees Celsius. NAN for unknown temperature
598
+
floatvoltage_v=3 [(mavsdk.options.default_value)="NaN"]; // Voltage in volts
599
+
floatcurrent_battery_a=4 [(mavsdk.options.default_value)="NaN"]; // Battery current in Amps, NAN if autopilot does not measure the current
600
+
floatcapacity_consumed_ah=5 [(mavsdk.options.default_value)="NaN"]; // Consumed charge in Amp hours, NAN if autopilot does not provide consumption estimate
601
+
floatremaining_percent=6 [(mavsdk.options.default_value)="NaN"]; // Estimated battery remaining (range: 0 to 100)
0 commit comments