Skip to content

Commit

Permalink
platforms/nuttx: Remove unnecessary sched_lock() from task spawn logic
Browse files Browse the repository at this point in the history
Starting a new task does not require that the scheduler is locked, this is
done in nsh only because nsh uses waitpid() to wait for the task to exit
and record its exit status.

The exit status does not interest us whatsoever -> remove the locking.

Also, we don't need to explicitly change a tasks priority when it is
created by px4_task_spawn_cmd, as task_create() already sets the priority
via nxthread_setup_scheduler().
  • Loading branch information
pussuw committed Nov 28, 2024
1 parent f0f87e4 commit a98bfa6
Show file tree
Hide file tree
Showing 2 changed files with 0 additions and 18 deletions.
8 changes: 0 additions & 8 deletions platforms/nuttx/src/px4/common/cdc_acm_check.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}
}
}
Expand All @@ -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;
}
Expand Down
10 changes: 0 additions & 10 deletions platforms/nuttx/src/px4/common/tasks.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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, &param);
}

sched_unlock();

return pid;
}

Expand Down

0 comments on commit a98bfa6

Please sign in to comment.