Use OS independent API for task creation/deletion

Calls to task_delete and task_spawn_cmd are now
px4_task_delete and px4_task_spawn_cmd respectively.

The px4_tasks.h header was added to the affected files
and incusions of nuttx/config.h were removed.

Signed-off-by: Mark Charlebois <charlebm@gmail.com>
This commit is contained in:
Mark Charlebois
2015-03-11 11:10:53 -07:00
parent 51a71d54c6
commit ddb32742eb
32 changed files with 94 additions and 88 deletions
@@ -36,6 +36,7 @@
*
* @author Thomas Gubler <thomasgubler@gmail.com>
*/
#include <px4_tasks.h>
#include <string.h>
#include <cstdlib>
#include <systemlib/err.h>
@@ -68,12 +69,12 @@ int publisher_main(int argc, char *argv[])
task_should_exit = false;
daemon_task = task_spawn_cmd("publisher",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
2000,
main,
(argv) ? (char * const *)&argv[2] : (char * const *)NULL);
daemon_task = px4_task_spawn_cmd("publisher",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
2000,
main,
(argv) ? (char* const*)&argv[2] : (char* const*)NULL);
exit(0);
}
+3 -3
View File
@@ -39,7 +39,7 @@
* @author Lorenz Meier <lorenz@px4.io>
*/
#include <nuttx/config.h>
#include <px4_tasks.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
@@ -408,7 +408,7 @@ usage(const char *reason)
* Makefile does only apply to this management task.
*
* The actual stack size should be set in the call
* to task_spawn_cmd().
* to px4_task_spawn_cmd().
*/
int rover_steering_control_main(int argc, char *argv[])
{
@@ -425,7 +425,7 @@ int rover_steering_control_main(int argc, char *argv[])
}
thread_should_exit = false;
deamon_task = task_spawn_cmd("rover_steering_control",
deamon_task = px4_task_spawn_cmd("rover_steering_control",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 20,
2048,
@@ -36,6 +36,7 @@
*
* @author Thomas Gubler <thomasgubler@gmail.com>
*/
#include <px4_tasks.h>
#include <string.h>
#include <cstdlib>
#include <systemlib/err.h>
@@ -68,12 +69,12 @@ int subscriber_main(int argc, char *argv[])
task_should_exit = false;
daemon_task = task_spawn_cmd("subscriber",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
2000,
main,
(argv) ? (char * const *)&argv[2] : (char * const *)NULL);
daemon_task = px4_task_spawn_cmd("subscriber",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
2000,
main,
(argv) ? (char* const*)&argv[2] : (char* const*)NULL);
exit(0);
}