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:
Andrew Tridgell 2016-10-28 10:05:40 +11:00
parent 34718b130a
commit 1b46a71596
1 changed files with 2 additions and 0 deletions

View File

@ -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,