Skip to content

Commit

Permalink
GCS_MAVLink: send GCS voltage to GCS
Browse files Browse the repository at this point in the history
may be resting voltage of option enabled
  • Loading branch information
tridge authored and peterbarker committed Mar 22, 2022
1 parent 9c067f3 commit 73eabb1
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions libraries/GCS_MAVLink/GCS_Common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -258,7 +258,7 @@ void GCS_MAVLINK::send_battery_status(const uint8_t instance) const
// for battery monitors that cannot provide voltages for individual cells the battery's total voltage is put into the first cell
// if the total voltage cannot fit into a single field, the remainder into subsequent fields.
// the GCS can then recover the pack voltage by summing all non ignored cell values an we can report a pack up to 655.34 V
float voltage = battery.voltage(instance) * 1e3f;
float voltage = battery.gcs_voltage(instance) * 1e3f;
for (uint8_t i = 0; i < MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN; i++) {
if (voltage < 0.001f) {
// too small to send to the GCS, set it to the no cell value
Expand Down Expand Up @@ -4919,7 +4919,7 @@ void GCS_MAVLINK::send_sys_status()
control_sensors_health,
static_cast<uint16_t>(AP::scheduler().load_average() * 1000),
#if !defined(HAL_BUILD_AP_PERIPH) || defined(HAL_PERIPH_ENABLE_BATTERY)
battery.voltage() * 1000, // mV
battery.gcs_voltage() * 1000, // mV
battery_current, // in 10mA units
battery_remaining, // in %
#else
Expand Down

0 comments on commit 73eabb1

Please sign in to comment.