Skip to content

Commit

Permalink
AP_DDS: fixed cell voltages
Browse files Browse the repository at this point in the history
the std:copy was copying from uint16_t to float
  • Loading branch information
tridge authored and Ryanf55 committed Aug 24, 2024
1 parent f984de4 commit dc6bd29
Showing 1 changed file with 5 additions and 2 deletions.
7 changes: 5 additions & 2 deletions libraries/AP_DDS/AP_DDS_Client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}
}
}

Expand Down

0 comments on commit dc6bd29

Please sign in to comment.