MAVLink app: Fix boot-time race between receive thread and instantiation.

This commit is contained in:
Lorenz Meier
2017-10-07 13:02:28 +02:00
parent 2246b54e2b
commit dd7b72dfb0

View File

@@ -1988,9 +1988,6 @@ Mavlink::task_main(int argc, char *argv[])
/* Initialize system properties */
mavlink_update_system();
/* start the MAVLink receiver */
MavlinkReceiver::receive_start(&_receive_thread, this);
MavlinkOrbSubscription *param_sub = add_orb_subscription(ORB_ID(parameter_update));
uint64_t param_time = 0;
MavlinkOrbSubscription *status_sub = add_orb_subscription(ORB_ID(vehicle_status));
@@ -2180,6 +2177,9 @@ Mavlink::task_main(int argc, char *argv[])
send_autopilot_capabilites();
}
/* start the MAVLink receiver last to avoid a race */
MavlinkReceiver::receive_start(&_receive_thread, this);
while (!_task_should_exit) {
/* main loop */
usleep(_main_loop_delay);