mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-02 05:04:08 +08:00
system: never call task_delete on nuttx, never force stop tasks
This commit is contained in:
parent
e4fc3022f2
commit
eba9276e6f
@ -239,21 +239,9 @@ public:
|
||||
unlock_module();
|
||||
px4_usleep(10000); // 10 ms
|
||||
lock_module();
|
||||
|
||||
if (++i > 500 && _task_id != -1) { // wait at most 5 sec
|
||||
PX4_ERR("timeout, forcing stop");
|
||||
|
||||
if (_task_id != task_id_is_work_queue) {
|
||||
px4_task_delete(_task_id);
|
||||
}
|
||||
|
||||
_task_id = -1;
|
||||
|
||||
delete _object.load();
|
||||
_object.store(nullptr);
|
||||
|
||||
ret = -1;
|
||||
break;
|
||||
i++;
|
||||
if (i % 500 == 0) {
|
||||
PX4_INFO("Waiting for task to stop...");
|
||||
}
|
||||
} while (_task_id != -1);
|
||||
|
||||
|
||||
@ -45,6 +45,7 @@
|
||||
#include <nuttx/kthread.h>
|
||||
|
||||
#include <sys/wait.h>
|
||||
#include <syslog.h>
|
||||
#include <stdbool.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
@ -88,7 +89,8 @@ int px4_task_spawn_cmd(const char *name, int scheduler, int priority, int stack_
|
||||
|
||||
int px4_task_delete(int pid)
|
||||
{
|
||||
return task_delete(pid);
|
||||
syslog(LOG_ERR, "Ignoring force task delete on NuttX\n");
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
const char *px4_get_taskname(void)
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user