Skip to content

Commit

Permalink
ina238: increase retries and only publish not connected if register c…
Browse files Browse the repository at this point in the history
…heck fails
  • Loading branch information
AlexKlimaj committed Jan 6, 2025
1 parent 76da62a commit 8da3c6d
Show file tree
Hide file tree
Showing 3 changed files with 12 additions and 5 deletions.
Binary file modified boards/ark/fpv/extras/ark_fpv_bootloader.bin
Binary file not shown.
3 changes: 3 additions & 0 deletions boards/ark/fpv/src/board_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -176,6 +176,9 @@

#define BOARD_BATTERY1_V_DIV (21.0f) // (20k + 1k) / 1k = 21

#define BOARD_BATTERY_ADC_VOLTAGE_FILTER_S 0.075f
#define BOARD_BATTERY_ADC_CURRENT_FILTER_S 0.125f

#define ADC_SCALED_PAYLOAD_SENSE ADC_SCALED_12V_CHANNEL

/* HW has to large of R termination on ADC todo:change when HW value is chosen */
Expand Down
14 changes: 9 additions & 5 deletions src/drivers/power_monitor/ina238/ina238.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -98,7 +98,7 @@ int INA238::read(uint8_t address, uint16_t &data)
uint16_t received_bytes;
int ret = PX4_ERROR;

for (size_t i = 0; i < 3; i++) {
for (size_t i = 0; i < 6; i++) {
ret = transfer(&address, 1, (uint8_t *)&received_bytes, sizeof(received_bytes));

if (ret == PX4_OK) {
Expand Down Expand Up @@ -240,6 +240,10 @@ int INA238::collect()
_battery.updateVoltage(static_cast<float>(bus_voltage * INA238_VSCALE));
_battery.updateCurrent(static_cast<float>(current * _current_lsb));
_battery.updateTemperature(static_cast<float>(temperature * INA238_TSCALE));

_battery.setConnected(success);

_battery.updateAndPublishBatteryStatus(hrt_absolute_time());
}

if (!success || hrt_elapsed_time(&_last_config_check_timestamp) > 100_ms) {
Expand All @@ -253,12 +257,12 @@ int INA238::collect()
PX4_DEBUG("register check failed");
perf_count(_bad_register_perf);
success = false;
}
}

_battery.setConnected(success);
_battery.setConnected(success);

_battery.updateAndPublishBatteryStatus(hrt_absolute_time());
_battery.updateAndPublishBatteryStatus(hrt_absolute_time());
}
}

perf_end(_sample_perf);

Expand Down

0 comments on commit 8da3c6d

Please sign in to comment.