diff options
author | Mark Charlebois <charlebm@gmail.com> | 2015-03-11 11:10:53 -0700 |
---|---|---|
committer | Mark Charlebois <charlebm@gmail.com> | 2015-04-20 10:49:44 -0700 |
commit | ddb32742ebd299e83e268c7ffa99c808bdaf4f8a (patch) | |
tree | a707ecef8356de7ae8629d1f3e0d3f7c29dd4434 /src/drivers | |
parent | 51a71d54c6fd55c81c92b75fbd59c3801e010600 (diff) | |
download | px4-firmware-ddb32742ebd299e83e268c7ffa99c808bdaf4f8a.tar.gz px4-firmware-ddb32742ebd299e83e268c7ffa99c808bdaf4f8a.tar.bz2 px4-firmware-ddb32742ebd299e83e268c7ffa99c808bdaf4f8a.zip |
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>
Diffstat (limited to 'src/drivers')
-rw-r--r-- | src/drivers/gps/gps.cpp | 6 | ||||
-rw-r--r-- | src/drivers/hil/hil.cpp | 6 | ||||
-rw-r--r-- | src/drivers/hott/hott_sensors/hott_sensors.cpp | 4 | ||||
-rw-r--r-- | src/drivers/hott/hott_telemetry/hott_telemetry.cpp | 4 | ||||
-rw-r--r-- | src/drivers/md25/md25_main.cpp | 4 | ||||
-rw-r--r-- | src/drivers/mkblctrl/mkblctrl.cpp | 6 | ||||
-rw-r--r-- | src/drivers/px4fmu/fmu.cpp | 6 | ||||
-rw-r--r-- | src/drivers/px4io/px4io.cpp | 6 | ||||
-rw-r--r-- | src/drivers/roboclaw/roboclaw_main.cpp | 4 |
9 files changed, 23 insertions, 23 deletions
diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp index 714c80ded..b727c5540 100644 --- a/src/drivers/gps/gps.cpp +++ b/src/drivers/gps/gps.cpp @@ -51,7 +51,7 @@ #include <math.h> #include <unistd.h> #include <fcntl.h> -#include <nuttx/config.h> +#include <px4_tasks.h> #include <nuttx/arch.h> #include <arch/board/board.h> #include <drivers/drv_hrt.h> @@ -213,7 +213,7 @@ GPS::~GPS() /* well, kill it anyway, though this will probably crash */ if (_task != -1) - task_delete(_task); + px4_task_delete(_task); g_dev = nullptr; @@ -229,7 +229,7 @@ GPS::init() goto out; /* start the GPS driver worker task */ - _task = task_spawn_cmd("gps", SCHED_DEFAULT, + _task = px4_task_spawn_cmd("gps", SCHED_DEFAULT, SCHED_PRIORITY_SLOW_DRIVER, 1500, (main_t)&GPS::task_main_trampoline, nullptr); if (_task < 0) { diff --git a/src/drivers/hil/hil.cpp b/src/drivers/hil/hil.cpp index 961ec4724..a82dec8ac 100644 --- a/src/drivers/hil/hil.cpp +++ b/src/drivers/hil/hil.cpp @@ -48,7 +48,7 @@ * driver. Use instead the normal FMU or IO driver. */ -#include <nuttx/config.h> +#include <px4_tasks.h> #include <sys/types.h> #include <stdint.h> @@ -188,7 +188,7 @@ HIL::~HIL() /* if we have given up, kill it */ if (--i == 0) { - task_delete(_task); + px4_task_delete(_task); break; } @@ -228,7 +228,7 @@ HIL::init() // gpio_reset(); /* start the HIL interface task */ - _task = task_spawn_cmd("fmuhil", + _task = px4_task_spawn_cmd("fmuhil", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, 1200, diff --git a/src/drivers/hott/hott_sensors/hott_sensors.cpp b/src/drivers/hott/hott_sensors/hott_sensors.cpp index 4ac7e4bdf..e5bbc41d1 100644 --- a/src/drivers/hott/hott_sensors/hott_sensors.cpp +++ b/src/drivers/hott/hott_sensors/hott_sensors.cpp @@ -42,7 +42,7 @@ */ #include <fcntl.h> -#include <nuttx/config.h> +#include <px4_tasks.h> #include <poll.h> #include <stdlib.h> #include <stdio.h> @@ -209,7 +209,7 @@ hott_sensors_main(int argc, char *argv[]) } thread_should_exit = false; - deamon_task = task_spawn_cmd(daemon_name, + deamon_task = px4_task_spawn_cmd(daemon_name, SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, 1024, diff --git a/src/drivers/hott/hott_telemetry/hott_telemetry.cpp b/src/drivers/hott/hott_telemetry/hott_telemetry.cpp index 43df0cb8c..841f3ed1a 100644 --- a/src/drivers/hott/hott_telemetry/hott_telemetry.cpp +++ b/src/drivers/hott/hott_telemetry/hott_telemetry.cpp @@ -44,7 +44,7 @@ */ #include <fcntl.h> -#include <nuttx/config.h> +#include <px4_tasks.h> #include <poll.h> #include <stdlib.h> #include <stdio.h> @@ -235,7 +235,7 @@ hott_telemetry_main(int argc, char *argv[]) } thread_should_exit = false; - deamon_task = task_spawn_cmd(daemon_name, + deamon_task = px4_task_spawn_cmd(daemon_name, SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, 2048, diff --git a/src/drivers/md25/md25_main.cpp b/src/drivers/md25/md25_main.cpp index d25d16fa1..7bcc1c9d6 100644 --- a/src/drivers/md25/md25_main.cpp +++ b/src/drivers/md25/md25_main.cpp @@ -44,7 +44,7 @@ * */ -#include <nuttx/config.h> +#include <px4_tasks.h> #include <unistd.h> #include <stdio.h> #include <stdlib.h> @@ -110,7 +110,7 @@ int md25_main(int argc, char *argv[]) } thread_should_exit = false; - deamon_task = task_spawn_cmd("md25", + deamon_task = px4_task_spawn_cmd("md25", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 10, 2048, diff --git a/src/drivers/mkblctrl/mkblctrl.cpp b/src/drivers/mkblctrl/mkblctrl.cpp index 3b8c4ee77..bf017103c 100644 --- a/src/drivers/mkblctrl/mkblctrl.cpp +++ b/src/drivers/mkblctrl/mkblctrl.cpp @@ -41,7 +41,7 @@ * */ -#include <nuttx/config.h> +#include <px4_tasks.h> #include <drivers/device/i2c.h> #include <systemlib/param/param.h> @@ -258,7 +258,7 @@ MK::~MK() /* if we have given up, kill it */ if (--i == 0) { - task_delete(_task); + px4_task_delete(_task); break; } @@ -302,7 +302,7 @@ MK::init(unsigned motors) } /* start the IO interface task */ - _task = task_spawn_cmd("mkblctrl", + _task = px4_task_spawn_cmd("mkblctrl", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 20, 1500, diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp index 92afc7cd7..f36a07b04 100644 --- a/src/drivers/px4fmu/fmu.cpp +++ b/src/drivers/px4fmu/fmu.cpp @@ -37,7 +37,7 @@ * Driver/configurator for the PX4 FMU multi-purpose port on v1 and v2 boards. */ -#include <nuttx/config.h> +#include <px4_tasks.h> #include <sys/types.h> #include <stdint.h> @@ -302,7 +302,7 @@ PX4FMU::~PX4FMU() /* if we have given up, kill it */ if (--i == 0) { - task_delete(_task); + px4_task_delete(_task); break; } @@ -341,7 +341,7 @@ PX4FMU::init() gpio_reset(); /* start the IO interface task */ - _task = task_spawn_cmd("fmuservo", + _task = px4_task_spawn_cmd("fmuservo", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, 1600, diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 33125699f..9fe69113b 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -38,7 +38,7 @@ * PX4IO is connected via I2C or DMA enabled high-speed UART. */ -#include <nuttx/config.h> +#include <px4_tasks.h> #include <sys/types.h> #include <stdint.h> @@ -550,7 +550,7 @@ PX4IO::~PX4IO() /* well, kill it anyway, though this will probably crash */ if (_task != -1) - task_delete(_task); + px4_task_delete(_task); if (_interface != nullptr) delete _interface; @@ -841,7 +841,7 @@ PX4IO::init() } /* start the IO interface task */ - _task = task_spawn_cmd("px4io", + _task = px4_task_spawn_cmd("px4io", SCHED_DEFAULT, SCHED_PRIORITY_ACTUATOR_OUTPUTS, 1800, diff --git a/src/drivers/roboclaw/roboclaw_main.cpp b/src/drivers/roboclaw/roboclaw_main.cpp index ea7178076..198e2f0c1 100644 --- a/src/drivers/roboclaw/roboclaw_main.cpp +++ b/src/drivers/roboclaw/roboclaw_main.cpp @@ -43,7 +43,7 @@ * */ -#include <nuttx/config.h> +#include <px4_tasks.h> #include <unistd.h> #include <stdio.h> #include <stdlib.h> @@ -105,7 +105,7 @@ int roboclaw_main(int argc, char *argv[]) } thread_should_exit = false; - deamon_task = task_spawn_cmd("roboclaw", + deamon_task = px4_task_spawn_cmd("roboclaw", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 10, 2048, |