diff --git a/platforms/nuttx/src/px4/common/cdc_acm_check.cpp b/platforms/nuttx/src/px4/common/cdc_acm_check.cpp index 6127c5ae84de..d2e18ce37b36 100644 --- a/platforms/nuttx/src/px4/common/cdc_acm_check.cpp +++ b/platforms/nuttx/src/px4/common/cdc_acm_check.cpp @@ -336,25 +336,19 @@ static void mavlink_usb_check(void *arg) #if defined(CONFIG_SERIAL_PASSTHRU_UBLOX) else if (launch_passthru) { - sched_lock(); exec_argv = (char **)gps_argv; px4_exec(exec_argv[0], exec_argv, nullptr, 0); - sched_unlock(); exec_argv = (char **)passthru_argv; } #endif - sched_lock(); - if (px4_exec(exec_argv[0], exec_argv, nullptr, 0) > 0) { usb_auto_start_state = UsbAutoStartState::connected; } else { usb_auto_start_state = UsbAutoStartState::disconnecting; } - - sched_unlock(); } } } @@ -374,10 +368,8 @@ static void mavlink_usb_check(void *arg) case UsbAutoStartState::connected: if (!vbus_present && !vbus_present_prev) { - sched_lock(); static const char *stop_argv[] {"mavlink", "stop", "-d", USB_DEVICE_PATH, NULL}; px4_exec(stop_argv[0], (char **)stop_argv, NULL, 0); - sched_unlock(); usb_auto_start_state = UsbAutoStartState::disconnecting; } diff --git a/platforms/nuttx/src/px4/common/tasks.cpp b/platforms/nuttx/src/px4/common/tasks.cpp index 07fb3c17760d..b6988bcb3466 100644 --- a/platforms/nuttx/src/px4/common/tasks.cpp +++ b/platforms/nuttx/src/px4/common/tasks.cpp @@ -64,8 +64,6 @@ int px4_task_spawn_cmd(const char *name, int scheduler, int priority, int stack_size, main_t entry, char *const argv[]) { - sched_lock(); - #if !defined(CONFIG_DISABLE_ENVIRON) && !defined(CONFIG_BUILD_KERNEL) /* None of the modules access the environment variables (via getenv() for instance), so delete them * all. They are only used within the startup script, and NuttX automatically exports them to the children @@ -82,14 +80,6 @@ int px4_task_spawn_cmd(const char *name, int scheduler, int priority, int stack_ int pid = kthread_create(name, priority, stack_size, entry, argv); #endif - if (pid > 0) { - /* configure the scheduler */ - struct sched_param param = { .sched_priority = priority }; - sched_setscheduler(pid, scheduler, ¶m); - } - - sched_unlock(); - return pid; }