mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
Rover: base SYS_STATUS load average on variable loop rate
This commit is contained in:
parent
b445313bf1
commit
d44c7f0886
@ -90,7 +90,7 @@ void Rover::send_extended_status1(mavlink_channel_t chan)
|
||||
control_sensors_present,
|
||||
control_sensors_enabled,
|
||||
control_sensors_health,
|
||||
static_cast<uint16_t>(scheduler.load_average(20000) * 1000),
|
||||
static_cast<uint16_t>(scheduler.load_average() * 1000),
|
||||
battery.voltage() * 1000, // mV
|
||||
battery_current, // in 10mA units
|
||||
battery_remaining, // in %
|
||||
|
Loading…
Reference in New Issue
Block a user