diff --git a/nuttx-configs/px4fmu-v5/nsh/defconfig b/nuttx-configs/px4fmu-v5/nsh/defconfig index bc25a9f1abaa..897d3e1723cf 100644 --- a/nuttx-configs/px4fmu-v5/nsh/defconfig +++ b/nuttx-configs/px4fmu-v5/nsh/defconfig @@ -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" diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index aa441951a927..0b90d4583f40 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -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);