mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 14:48:28 -04:00
AP_BattMonitor: changes from PR review
This commit is contained in:
parent
05a8a5c173
commit
9638f6cab9
@ -29,7 +29,7 @@ void AP_BattMonitor_BLHeliESC::init(void)
|
|||||||
|
|
||||||
void AP_BattMonitor_BLHeliESC::read(void)
|
void AP_BattMonitor_BLHeliESC::read(void)
|
||||||
{
|
{
|
||||||
AP_BLHeli *blheli = AP_BLHeli::get_instance();
|
AP_BLHeli *blheli = AP_BLHeli::get_singleton();
|
||||||
if (!blheli) {
|
if (!blheli) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@ -42,21 +42,25 @@ void AP_BattMonitor_BLHeliESC::read(void)
|
|||||||
uint32_t now = AP_HAL::millis();
|
uint32_t now = AP_HAL::millis();
|
||||||
uint32_t highest_ms=0;
|
uint32_t highest_ms=0;
|
||||||
|
|
||||||
for (uint8_t i=0; i<8; i++) {
|
for (uint8_t i=0; i<AP_BLHELI_MAX_ESCS; i++) {
|
||||||
AP_BLHeli::telem_data td;
|
AP_BLHeli::telem_data td;
|
||||||
uint32_t timestamp_ms;
|
blheli->get_telem_data(i, td);
|
||||||
blheli->get_telem_data(i, td, timestamp_ms);
|
|
||||||
if (now - timestamp_ms > 1000) {
|
// accumulate consumed_sum regardless of age, to cope with ESC
|
||||||
|
// dropping out
|
||||||
|
consumed_sum += td.consumption;
|
||||||
|
|
||||||
|
if (now - td.timestamp_ms > 1000) {
|
||||||
// don't use old data
|
// don't use old data
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
|
|
||||||
num_escs++;
|
num_escs++;
|
||||||
voltage_sum += td.voltage;
|
voltage_sum += td.voltage;
|
||||||
current_sum += td.current;
|
current_sum += td.current;
|
||||||
consumed_sum += td.consumption;
|
|
||||||
temperature_sum += td.temperature;
|
temperature_sum += td.temperature;
|
||||||
if (timestamp_ms > highest_ms) {
|
if (td.timestamp_ms > highest_ms) {
|
||||||
highest_ms = timestamp_ms;
|
highest_ms = td.timestamp_ms;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -73,6 +77,12 @@ void AP_BattMonitor_BLHeliESC::read(void)
|
|||||||
_state.consumed_mah = consumed_sum;
|
_state.consumed_mah = consumed_sum;
|
||||||
_state.last_time_micros = highest_ms * 1000;
|
_state.last_time_micros = highest_ms * 1000;
|
||||||
_state.temperature_time = highest_ms;
|
_state.temperature_time = highest_ms;
|
||||||
|
|
||||||
|
if (current_sum > 0) {
|
||||||
|
// if we have ever got a current value then we know we have a
|
||||||
|
// current sensor
|
||||||
|
have_current = true;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // HAVE_AP_BLHELI_SUPPORT
|
#endif // HAVE_AP_BLHELI_SUPPORT
|
||||||
|
@ -35,5 +35,8 @@ public:
|
|||||||
void read() override;
|
void read() override;
|
||||||
|
|
||||||
// BLHeliESC provides current info
|
// BLHeliESC provides current info
|
||||||
bool has_current() const override { return true; };
|
bool has_current() const override { return have_current; };
|
||||||
|
|
||||||
|
private:
|
||||||
|
bool have_current;
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user