Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix MAVLink app startup race during boot #8081

Merged
merged 2 commits into from
Oct 7, 2017
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion nuttx-configs/px4fmu-v5/nsh/defconfig
Original file line number Diff line number Diff line change
Expand Up @@ -962,7 +962,7 @@ CONFIG_CDCACM_NRDREQS=4
CONFIG_CDCACM_NWRREQS=4
CONFIG_CDCACM_BULKIN_REQLEN=96
CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=8000
CONFIG_CDCACM_TXBUFSIZE=12000
CONFIG_CDCACM_VENDORID=0x26ac
CONFIG_CDCACM_PRODUCTID=0x0032
CONFIG_CDCACM_VENDORSTR="3D Robotics"
Expand Down
6 changes: 3 additions & 3 deletions src/modules/mavlink/mavlink_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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));
Expand Down Expand Up @@ -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);
Expand Down