Copter: base SYS_STATUS load average on variable loop rate
This commit is contained in:
parent
d44c7f0886
commit
31b33b2232
@ -123,7 +123,7 @@ NOINLINE void Copter::send_extended_status1(mavlink_channel_t chan)
|
||||
control_sensors_present,
|
||||
control_sensors_enabled,
|
||||
control_sensors_health,
|
||||
(uint16_t)(scheduler.load_average(MAIN_LOOP_MICROS) * 1000),
|
||||
(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