Skip to content

telemetry: add energy_consumed_wh to Battery#2882

Open
bansiesta wants to merge 1 commit into
mavlink:mainfrom
bansiesta:feat/battery-energy-consumed
Open

telemetry: add energy_consumed_wh to Battery#2882
bansiesta wants to merge 1 commit into
mavlink:mainfrom
bansiesta:feat/battery-energy-consumed

Conversation

@bansiesta
Copy link
Copy Markdown
Collaborator

Summary

Fixes #1748 — exposes the energy_consumed field from the MAVLink BATTERY_STATUS message which was previously ignored.

Changes

  • C++ (telemetry.hpp): Added energy_consumed_wh field to Battery struct
  • C++ (telemetry.cpp): Updated operator== and operator<< for Battery
  • C++ (telemetry_impl.cpp): Populated energy_consumed_wh in process_battery_status() — converts from hectojoules (hJ, the MAVLink unit) to Watt-hours: energy_consumed / 36.0f (1 hJ = 100 J, 1 Wh = 3600 J). Sentinel value −1 (not available) maps to NaN.
  • C binding (telemetry.h, telemetry.cpp): Added field to mavsdk_telemetry_battery_t and translation functions
  • Python binding (telemetry.py): Added field to BatteryCStruct, Battery.__init__, Battery.from_c_struct, Battery.to_c_struct, and Battery.__str__

Notes

The proto definition (telemetry.proto) has a companion PR in MAVSDK-Proto adding float energy_consumed_wh = 9 to the Battery message. The .pb.h/.pb.cc generated files need to be regenerated once that proto PR merges (requires protoc 29.1).

@bansiesta bansiesta changed the title feat(telemetry): add energy_consumed_wh to Battery telemetry: add energy_consumed_wh to Battery May 20, 2026
@bansiesta bansiesta force-pushed the feat/battery-energy-consumed branch from 053e5b9 to 9b143bb Compare May 20, 2026 03:19
bansiesta added a commit to bansiesta/MAVSDK-Proto that referenced this pull request May 20, 2026
Exposes the energy_consumed field from BATTERY_STATUS MAVLink message
as a new float field in Watt-hours. Sentinel value -1 maps to NaN.

Companion PR: mavlink/MAVSDK#2882
Exposes the energy_consumed field from BATTERY_STATUS MAVLink message.
Converts from hectojoules (hJ) to Watt-hours (Wh) by dividing by 36
(1 hJ = 100 J, 1 Wh = 3600 J). Reports NaN when autopilot signals
the field is unavailable (sentinel value -1).

Fixes mavlink#1748
@bansiesta bansiesta force-pushed the feat/battery-energy-consumed branch from 9b143bb to 89a59b0 Compare May 20, 2026 03:30
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

Battery telemetry raw current values

1 participant