From 6f867e29d0896e5e860dff346dc9aca03cb0475b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 10 Jul 2024 15:43:25 +1000 Subject: [PATCH] AP_DDS: fixed cell voltages the std:copy was copying from uint16_t to float --- libraries/AP_DDS/AP_DDS_Client.cpp | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/libraries/AP_DDS/AP_DDS_Client.cpp b/libraries/AP_DDS/AP_DDS_Client.cpp index 0166f2284a16c..6d7902f3e43c0 100644 --- a/libraries/AP_DDS/AP_DDS_Client.cpp +++ b/libraries/AP_DDS/AP_DDS_Client.cpp @@ -305,8 +305,11 @@ void AP_DDS_Client::update_topic(sensor_msgs_msg_BatteryState& msg, const uint8_ msg.power_supply_technology = 0; //POWER_SUPPLY_TECHNOLOGY_UNKNOWN if (battery.has_cell_voltages(instance)) { - const uint16_t* cellVoltages = battery.get_cell_voltages(instance).cells; - std::copy(cellVoltages, cellVoltages + AP_BATT_MONITOR_CELLS_MAX, msg.cell_voltage); + const auto &cells = battery.get_cell_voltages(instance); + const uint8_t ncells_max = MIN(ARRAY_SIZE(msg.cell_voltage), ARRAY_SIZE(cells.cells)); + for (uint8_t i=0; i< ncells_max; i++) { + msg.cell_voltage[i] = cells.cells[i] * 0.001; + } } }