mirror of https://github.com/ArduPilot/ardupilot
Copter: also update sensor status before mavlink send
this removes the 1 second lag in updates when using the one second loop
This commit is contained in:
parent
34718b130a
commit
1b46a71596
|
@ -116,6 +116,8 @@ NOINLINE void Copter::send_extended_status1(mavlink_channel_t chan)
|
||||||
battery_current = battery.current_amps() * 100;
|
battery_current = battery.current_amps() * 100;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
update_sensor_status_flags();
|
||||||
|
|
||||||
mavlink_msg_sys_status_send(
|
mavlink_msg_sys_status_send(
|
||||||
chan,
|
chan,
|
||||||
control_sensors_present,
|
control_sensors_present,
|
||||||
|
|
Loading…
Reference in New Issue