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

View File

@@ -31,7 +31,7 @@
*
****************************************************************************/
#include <nuttx/config.h>
#include <px4_tasks.h>
#include <cstdlib>
#include <cstring>
@@ -109,7 +109,7 @@ UavcanNode::~UavcanNode()
/* if we have given up, kill it */
if (--i == 0) {
task_delete(_task);
px4_task_delete(_task);
break;
}
@@ -194,7 +194,7 @@ int UavcanNode::start(uavcan::NodeID node_id, uint32_t bitrate)
* Start the task. Normally it should never exit.
*/
static auto run_trampoline = [](int, char *[]) {return UavcanNode::_instance->run();};
_instance->_task = task_spawn_cmd("uavcan", SCHED_DEFAULT, SCHED_PRIORITY_ACTUATOR_OUTPUTS, StackSize,
_instance->_task = px4_task_spawn_cmd("uavcan", SCHED_DEFAULT, SCHED_PRIORITY_ACTUATOR_OUTPUTS, StackSize,
static_cast<main_t>(run_trampoline), nullptr);
if (_instance->_task < 0) {