aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--src/drivers/gps/gps.cpp6
-rw-r--r--src/drivers/hil/hil.cpp6
-rw-r--r--src/drivers/hott/hott_sensors/hott_sensors.cpp4
-rw-r--r--src/drivers/hott/hott_telemetry/hott_telemetry.cpp4
-rw-r--r--src/drivers/md25/md25_main.cpp4
-rw-r--r--src/drivers/mkblctrl/mkblctrl.cpp6
-rw-r--r--src/drivers/px4fmu/fmu.cpp6
-rw-r--r--src/drivers/px4io/px4io.cpp6
-rw-r--r--src/drivers/roboclaw/roboclaw_main.cpp4
-rw-r--r--src/examples/publisher/publisher_start_nuttx.cpp3
-rw-r--r--src/examples/rover_steering_control/main.cpp6
-rw-r--r--src/examples/subscriber/subscriber_start_nuttx.cpp3
-rwxr-xr-xsrc/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp6
-rwxr-xr-xsrc/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp6
-rw-r--r--src/modules/bottle_drop/bottle_drop.cpp6
-rw-r--r--src/modules/commander/commander.cpp4
-rw-r--r--src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp6
-rw-r--r--src/modules/fixedwing_backside/fixedwing_backside_main.cpp4
-rw-r--r--src/modules/fw_att_control/fw_att_control_main.cpp6
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp6
-rw-r--r--src/modules/land_detector/land_detector_main.cpp5
-rw-r--r--src/modules/mavlink/mavlink_main.cpp6
-rw-r--r--src/modules/mc_att_control/mc_att_control_main.cpp6
-rw-r--r--src/modules/mc_att_control_multiplatform/mc_att_control_start_nuttx.cpp3
-rw-r--r--src/modules/mc_pos_control/mc_pos_control_main.cpp5
-rw-r--r--src/modules/mc_pos_control_multiplatform/mc_pos_control_start_nuttx.cpp3
-rw-r--r--src/modules/navigator/navigator_main.cpp6
-rw-r--r--src/modules/segway/segway_main.cpp4
-rw-r--r--src/modules/sensors/sensors.cpp6
-rw-r--r--src/modules/uORB/uORB.cpp4
-rw-r--r--src/modules/uavcan/uavcan_main.cpp6
-rw-r--r--src/modules/vtol_att_control/vtol_att_control_main.cpp6
32 files changed, 78 insertions, 84 deletions
diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp
index b727c5540..714c80ded 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 <px4_tasks.h>
+#include <nuttx/config.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)
- px4_task_delete(_task);
+ task_delete(_task);
g_dev = nullptr;
@@ -229,7 +229,7 @@ GPS::init()
goto out;
/* start the GPS driver worker task */
- _task = px4_task_spawn_cmd("gps", SCHED_DEFAULT,
+ _task = 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 a82dec8ac..961ec4724 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 <px4_tasks.h>
+#include <nuttx/config.h>
#include <sys/types.h>
#include <stdint.h>
@@ -188,7 +188,7 @@ HIL::~HIL()
/* if we have given up, kill it */
if (--i == 0) {
- px4_task_delete(_task);
+ task_delete(_task);
break;
}
@@ -228,7 +228,7 @@ HIL::init()
// gpio_reset();
/* start the HIL interface task */
- _task = px4_task_spawn_cmd("fmuhil",
+ _task = 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 e5bbc41d1..4ac7e4bdf 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 <px4_tasks.h>
+#include <nuttx/config.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 = px4_task_spawn_cmd(daemon_name,
+ deamon_task = 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 841f3ed1a..43df0cb8c 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 <px4_tasks.h>
+#include <nuttx/config.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 = px4_task_spawn_cmd(daemon_name,
+ deamon_task = 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 7bcc1c9d6..d25d16fa1 100644
--- a/src/drivers/md25/md25_main.cpp
+++ b/src/drivers/md25/md25_main.cpp
@@ -44,7 +44,7 @@
*
*/
-#include <px4_tasks.h>
+#include <nuttx/config.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 = px4_task_spawn_cmd("md25",
+ deamon_task = 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 bf017103c..3b8c4ee77 100644
--- a/src/drivers/mkblctrl/mkblctrl.cpp
+++ b/src/drivers/mkblctrl/mkblctrl.cpp
@@ -41,7 +41,7 @@
*
*/
-#include <px4_tasks.h>
+#include <nuttx/config.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) {
- px4_task_delete(_task);
+ task_delete(_task);
break;
}
@@ -302,7 +302,7 @@ MK::init(unsigned motors)
}
/* start the IO interface task */
- _task = px4_task_spawn_cmd("mkblctrl",
+ _task = 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 f36a07b04..92afc7cd7 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 <px4_tasks.h>
+#include <nuttx/config.h>
#include <sys/types.h>
#include <stdint.h>
@@ -302,7 +302,7 @@ PX4FMU::~PX4FMU()
/* if we have given up, kill it */
if (--i == 0) {
- px4_task_delete(_task);
+ task_delete(_task);
break;
}
@@ -341,7 +341,7 @@ PX4FMU::init()
gpio_reset();
/* start the IO interface task */
- _task = px4_task_spawn_cmd("fmuservo",
+ _task = 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 9fe69113b..33125699f 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 <px4_tasks.h>
+#include <nuttx/config.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)
- px4_task_delete(_task);
+ task_delete(_task);
if (_interface != nullptr)
delete _interface;
@@ -841,7 +841,7 @@ PX4IO::init()
}
/* start the IO interface task */
- _task = px4_task_spawn_cmd("px4io",
+ _task = 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 198e2f0c1..ea7178076 100644
--- a/src/drivers/roboclaw/roboclaw_main.cpp
+++ b/src/drivers/roboclaw/roboclaw_main.cpp
@@ -43,7 +43,7 @@
*
*/
-#include <px4_tasks.h>
+#include <nuttx/config.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 = px4_task_spawn_cmd("roboclaw",
+ deamon_task = task_spawn_cmd("roboclaw",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 10,
2048,
diff --git a/src/examples/publisher/publisher_start_nuttx.cpp b/src/examples/publisher/publisher_start_nuttx.cpp
index 2f12e298b..aaf28fdb7 100644
--- a/src/examples/publisher/publisher_start_nuttx.cpp
+++ b/src/examples/publisher/publisher_start_nuttx.cpp
@@ -36,7 +36,6 @@
*
* @author Thomas Gubler <thomasgubler@gmail.com>
*/
-#include <px4_tasks.h>
#include <string.h>
#include <cstdlib>
#include <systemlib/err.h>
@@ -69,7 +68,7 @@ int publisher_main(int argc, char *argv[])
task_should_exit = false;
- daemon_task = px4_task_spawn_cmd("publisher",
+ daemon_task = task_spawn_cmd("publisher",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
2000,
diff --git a/src/examples/rover_steering_control/main.cpp b/src/examples/rover_steering_control/main.cpp
index 6fc4af4f4..41df96775 100644
--- a/src/examples/rover_steering_control/main.cpp
+++ b/src/examples/rover_steering_control/main.cpp
@@ -39,7 +39,7 @@
* @author Lorenz Meier <lorenz@px4.io>
*/
-#include <px4_tasks.h>
+#include <nuttx/config.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 px4_task_spawn_cmd().
+ * to 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 = px4_task_spawn_cmd("rover_steering_control",
+ deamon_task = task_spawn_cmd("rover_steering_control",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 20,
2048,
diff --git a/src/examples/subscriber/subscriber_start_nuttx.cpp b/src/examples/subscriber/subscriber_start_nuttx.cpp
index 091a15d2a..91543d5d2 100644
--- a/src/examples/subscriber/subscriber_start_nuttx.cpp
+++ b/src/examples/subscriber/subscriber_start_nuttx.cpp
@@ -36,7 +36,6 @@
*
* @author Thomas Gubler <thomasgubler@gmail.com>
*/
-#include <px4_tasks.h>
#include <string.h>
#include <cstdlib>
#include <systemlib/err.h>
@@ -69,7 +68,7 @@ int subscriber_main(int argc, char *argv[])
task_should_exit = false;
- daemon_task = px4_task_spawn_cmd("subscriber",
+ daemon_task = task_spawn_cmd("subscriber",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
2000,
diff --git a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
index 87a1b4876..b2a3572a7 100755
--- a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
+++ b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
@@ -41,7 +41,7 @@
* @author Thomas Gubler <thomasgubler@gmail.com>
*/
-#include <px4_tasks.h>
+#include <nuttx/config.h>
#include <unistd.h>
#include <stdlib.h>
#include <stdio.h>
@@ -114,7 +114,7 @@ usage(const char *reason)
* Makefile does only apply to this management task.
*
* The actual stack size should be set in the call
- * to px4_task_spawn_cmd().
+ * to task_spawn_cmd().
*/
int attitude_estimator_ekf_main(int argc, char *argv[])
{
@@ -131,7 +131,7 @@ int attitude_estimator_ekf_main(int argc, char *argv[])
}
thread_should_exit = false;
- attitude_estimator_ekf_task = px4_task_spawn_cmd("attitude_estimator_ekf",
+ attitude_estimator_ekf_task = task_spawn_cmd("attitude_estimator_ekf",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
7700,
diff --git a/src/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp b/src/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp
index 448f1c391..82bcbc66f 100755
--- a/src/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp
+++ b/src/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp
@@ -50,7 +50,7 @@
* [2] Euston, M.; Coote, P.; Mahony, R.; Jonghyuk Kim; Hamel, T., "A complementary filter for attitude estimation of a fixed-wing UAV," Intelligent Robots and Systems, 2008. IROS 2008. IEEE/RSJ International Conference on , vol., no., pp.340,345, 22-26 Sept. 2008
*/
-#include <px4_tasks.h>
+#include <nuttx/config.h>
#include <unistd.h>
#include <stdlib.h>
#include <string.h>
@@ -132,7 +132,7 @@ usage(const char *reason)
* Makefile does only apply to this management task.
*
* The actual stack size should be set in the call
- * to px4_task_spawn_cmd().
+ * to task_spawn_cmd().
*/
int attitude_estimator_so3_main(int argc, char *argv[])
{
@@ -149,7 +149,7 @@ int attitude_estimator_so3_main(int argc, char *argv[])
}
thread_should_exit = false;
- attitude_estimator_so3_task = px4_task_spawn_cmd("attitude_estimator_so3",
+ attitude_estimator_so3_task = task_spawn_cmd("attitude_estimator_so3",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
14000,
diff --git a/src/modules/bottle_drop/bottle_drop.cpp b/src/modules/bottle_drop/bottle_drop.cpp
index 3681bdb51..b267209fe 100644
--- a/src/modules/bottle_drop/bottle_drop.cpp
+++ b/src/modules/bottle_drop/bottle_drop.cpp
@@ -40,7 +40,7 @@
* @author Julian Oes <joes@student.ethz.ch>
*/
-#include <px4_tasks.h>
+#include <nuttx/config.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
@@ -210,7 +210,7 @@ BottleDrop::~BottleDrop()
/* if we have given up, kill it */
if (++i > 50) {
- px4_task_delete(_main_task);
+ task_delete(_main_task);
break;
}
} while (_main_task != -1);
@@ -225,7 +225,7 @@ BottleDrop::start()
ASSERT(_main_task == -1);
/* start the task */
- _main_task = px4_task_spawn_cmd("bottle_drop",
+ _main_task = task_spawn_cmd("bottle_drop",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT + 15,
1500,
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index bc118538b..bb1ed7f5d 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -42,7 +42,7 @@
* @author Anton Babushkin <anton.babushkin@me.com>
*/
-#include <px4_tasks.h>
+#include <nuttx/config.h>
#include <pthread.h>
#include <stdio.h>
#include <stdlib.h>
@@ -275,7 +275,7 @@ int commander_main(int argc, char *argv[])
}
thread_should_exit = false;
- daemon_task = px4_task_spawn_cmd("commander",
+ daemon_task = task_spawn_cmd("commander",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 40,
3400,
diff --git a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
index db817e2bc..e0b4cb2a0 100644
--- a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
+++ b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
@@ -43,7 +43,7 @@
#include "AttitudePositionEstimatorEKF.h"
#include "estimator_22states.h"
-#include <px4_tasks.h>
+#include <nuttx/config.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
@@ -281,7 +281,7 @@ AttitudePositionEstimatorEKF::~AttitudePositionEstimatorEKF()
/* if we have given up, kill it */
if (++i > 50) {
- px4_task_delete(_estimator_task);
+ task_delete(_estimator_task);
break;
}
} while (_estimator_task != -1);
@@ -1035,7 +1035,7 @@ int AttitudePositionEstimatorEKF::start()
ASSERT(_estimator_task == -1);
/* start the task */
- _estimator_task = px4_task_spawn_cmd("ekf_att_pos_estimator",
+ _estimator_task = task_spawn_cmd("ekf_att_pos_estimator",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 40,
7500,
diff --git a/src/modules/fixedwing_backside/fixedwing_backside_main.cpp b/src/modules/fixedwing_backside/fixedwing_backside_main.cpp
index 4c0a7d36d..bd1486324 100644
--- a/src/modules/fixedwing_backside/fixedwing_backside_main.cpp
+++ b/src/modules/fixedwing_backside/fixedwing_backside_main.cpp
@@ -39,7 +39,7 @@
* Fixedwing backside controller using control library
*/
-#include <px4_tasks.h>
+#include <nuttx/config.h>
#include <unistd.h>
#include <stdio.h>
#include <stdlib.h>
@@ -111,7 +111,7 @@ int fixedwing_backside_main(int argc, char *argv[])
thread_should_exit = false;
- deamon_task = px4_task_spawn_cmd("fixedwing_backside",
+ deamon_task = task_spawn_cmd("fixedwing_backside",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 10,
5120,
diff --git a/src/modules/fw_att_control/fw_att_control_main.cpp b/src/modules/fw_att_control/fw_att_control_main.cpp
index 43124db89..0a8d07fed 100644
--- a/src/modules/fw_att_control/fw_att_control_main.cpp
+++ b/src/modules/fw_att_control/fw_att_control_main.cpp
@@ -41,7 +41,7 @@
*
*/
-#include <px4_tasks.h>
+#include <nuttx/config.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
@@ -424,7 +424,7 @@ FixedwingAttitudeControl::~FixedwingAttitudeControl()
/* if we have given up, kill it */
if (++i > 50) {
- px4_task_delete(_control_task);
+ task_delete(_control_task);
break;
}
} while (_control_task != -1);
@@ -1117,7 +1117,7 @@ FixedwingAttitudeControl::start()
ASSERT(_control_task == -1);
/* start the task */
- _control_task = px4_task_spawn_cmd("fw_att_control",
+ _control_task = task_spawn_cmd("fw_att_control",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
1600,
diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
index 76093a5f9..34265d6a4 100644
--- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
+++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
@@ -51,7 +51,7 @@
* @author Thomas Gubler <thomasgubler@gmail.com>
*/
-#include <px4_tasks.h>
+#include <nuttx/config.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
@@ -542,7 +542,7 @@ FixedwingPositionControl::~FixedwingPositionControl()
/* if we have given up, kill it */
if (++i > 50) {
- px4_task_delete(_control_task);
+ task_delete(_control_task);
break;
}
} while (_control_task != -1);
@@ -1621,7 +1621,7 @@ FixedwingPositionControl::start()
ASSERT(_control_task == -1);
/* start the task */
- _control_task = px4_task_spawn_cmd("fw_pos_control_l1",
+ _control_task = task_spawn_cmd("fw_pos_control_l1",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
1600,
diff --git a/src/modules/land_detector/land_detector_main.cpp b/src/modules/land_detector/land_detector_main.cpp
index e0402419f..b4b7c33a2 100644
--- a/src/modules/land_detector/land_detector_main.cpp
+++ b/src/modules/land_detector/land_detector_main.cpp
@@ -38,7 +38,6 @@
* @author Johan Jansen <jnsn.johan@gmail.com>
*/
-#include <px4_tasks.h> //usleep
#include <unistd.h> //usleep
#include <stdio.h>
#include <string.h>
@@ -96,7 +95,7 @@ static void land_detector_stop()
/* if we have given up, kill it */
if (++i > 50) {
- px4_task_delete(_landDetectorTaskID);
+ task_delete(_landDetectorTaskID);
break;
}
} while (land_detector_task->isRunning());
@@ -137,7 +136,7 @@ static int land_detector_start(const char *mode)
}
//Start new thread task
- _landDetectorTaskID = px4_task_spawn_cmd("land_detector",
+ _landDetectorTaskID = task_spawn_cmd("land_detector",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
1000,
diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp
index 4956bbb9d..ba049bac4 100644
--- a/src/modules/mavlink/mavlink_main.cpp
+++ b/src/modules/mavlink/mavlink_main.cpp
@@ -39,7 +39,7 @@
* @author Anton Babushkin <anton.babushkin@me.com>
*/
-#include <px4_tasks.h>
+#include <nuttx/config.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
@@ -242,7 +242,7 @@ Mavlink::~Mavlink()
/* if we have given up, kill it */
if (++i > 50) {
//TODO store main task handle in Mavlink instance to allow killing task
- //px4_task_delete(_mavlink_task);
+ //task_delete(_mavlink_task);
break;
}
} while (_task_running);
@@ -1618,7 +1618,7 @@ Mavlink::start(int argc, char *argv[])
// between the starting task and the spawned
// task - start_helper() only returns
// when the started task exits.
- px4_task_spawn_cmd(buf,
+ task_spawn_cmd(buf,
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
2400,
diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp
index 8898433c8..3a0dfe4c3 100644
--- a/src/modules/mc_att_control/mc_att_control_main.cpp
+++ b/src/modules/mc_att_control/mc_att_control_main.cpp
@@ -53,7 +53,7 @@
* If rotation matrix setpoint is invalid it will be generated from Euler angles for compatibility with old position controllers.
*/
-#include <px4_tasks.h>
+#include <nuttx/config.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
@@ -404,7 +404,7 @@ MulticopterAttitudeControl::~MulticopterAttitudeControl()
/* if we have given up, kill it */
if (++i > 50) {
- px4_task_delete(_control_task);
+ task_delete(_control_task);
break;
}
} while (_control_task != -1);
@@ -905,7 +905,7 @@ MulticopterAttitudeControl::start()
ASSERT(_control_task == -1);
/* start the task */
- _control_task = px4_task_spawn_cmd("mc_att_control",
+ _control_task = task_spawn_cmd("mc_att_control",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
1600,
diff --git a/src/modules/mc_att_control_multiplatform/mc_att_control_start_nuttx.cpp b/src/modules/mc_att_control_multiplatform/mc_att_control_start_nuttx.cpp
index 6d16e0155..dec1e1745 100644
--- a/src/modules/mc_att_control_multiplatform/mc_att_control_start_nuttx.cpp
+++ b/src/modules/mc_att_control_multiplatform/mc_att_control_start_nuttx.cpp
@@ -36,7 +36,6 @@
*
* @author Thomas Gubler <thomasgubler@gmail.com>
*/
-#include <px4_tasks.h>
#include <string.h>
#include <cstdlib>
#include <systemlib/err.h>
@@ -69,7 +68,7 @@ int mc_att_control_m_main(int argc, char *argv[])
task_should_exit = false;
- daemon_task = px4_task_spawn_cmd("mc_att_control_m",
+ daemon_task = task_spawn_cmd("mc_att_control_m",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
1900,
diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp
index 867521cc2..5191a4de3 100644
--- a/src/modules/mc_pos_control/mc_pos_control_main.cpp
+++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp
@@ -50,7 +50,6 @@
*/
#include <px4.h>
-#include <px4_tasks.h>
#include <functional>
#include <cstdio>
#include <stdlib.h>
@@ -385,7 +384,7 @@ MulticopterPositionControl::~MulticopterPositionControl()
/* if we have given up, kill it */
if (++i > 50) {
- px4_task_delete(_control_task);
+ task_delete(_control_task);
break;
}
} while (_control_task != -1);
@@ -1424,7 +1423,7 @@ MulticopterPositionControl::start()
ASSERT(_control_task == -1);
/* start the task */
- _control_task = px4_task_spawn_cmd("mc_pos_control",
+ _control_task = task_spawn_cmd("mc_pos_control",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
1600,
diff --git a/src/modules/mc_pos_control_multiplatform/mc_pos_control_start_nuttx.cpp b/src/modules/mc_pos_control_multiplatform/mc_pos_control_start_nuttx.cpp
index bd67366cf..0db67d83f 100644
--- a/src/modules/mc_pos_control_multiplatform/mc_pos_control_start_nuttx.cpp
+++ b/src/modules/mc_pos_control_multiplatform/mc_pos_control_start_nuttx.cpp
@@ -36,7 +36,6 @@
*
* @author Thomas Gubler <thomasgubler@gmail.com>
*/
-#include <px4_tasks.h>
#include <string.h>
#include <cstdlib>
#include <systemlib/err.h>
@@ -69,7 +68,7 @@ int mc_pos_control_m_main(int argc, char *argv[])
task_should_exit = false;
- daemon_task = px4_task_spawn_cmd("mc_pos_control_m",
+ daemon_task = task_spawn_cmd("mc_pos_control_m",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
2500,
diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp
index dd0789265..9691e26a8 100644
--- a/src/modules/navigator/navigator_main.cpp
+++ b/src/modules/navigator/navigator_main.cpp
@@ -43,7 +43,7 @@
* @author Thomas Gubler <thomasgubler@gmail.com>
*/
-#include <px4_tasks.h>
+#include <nuttx/config.h>
#include <stdio.h>
#include <stdlib.h>
@@ -174,7 +174,7 @@ Navigator::~Navigator()
/* if we have given up, kill it */
if (++i > 50) {
- px4_task_delete(_navigator_task);
+ task_delete(_navigator_task);
break;
}
} while (_navigator_task != -1);
@@ -515,7 +515,7 @@ Navigator::start()
ASSERT(_navigator_task == -1);
/* start the task */
- _navigator_task = px4_task_spawn_cmd("navigator",
+ _navigator_task = task_spawn_cmd("navigator",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT + 20,
1800,
diff --git a/src/modules/segway/segway_main.cpp b/src/modules/segway/segway_main.cpp
index 7a4c4bb6f..b36d56d6d 100644
--- a/src/modules/segway/segway_main.cpp
+++ b/src/modules/segway/segway_main.cpp
@@ -39,7 +39,7 @@
* Segway controller using control library
*/
-#include <px4_tasks.h>
+#include <nuttx/config.h>
#include <unistd.h>
#include <stdio.h>
#include <stdlib.h>
@@ -106,7 +106,7 @@ int segway_main(int argc, char *argv[])
thread_should_exit = false;
- deamon_task = px4_task_spawn_cmd("segway",
+ deamon_task = task_spawn_cmd("segway",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 10,
5120,
diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp
index 751915380..3fc8627c1 100644
--- a/src/modules/sensors/sensors.cpp
+++ b/src/modules/sensors/sensors.cpp
@@ -46,7 +46,7 @@
* @author Anton Babushkin <anton@px4.io>
*/
-#include <px4_tasks.h>
+#include <nuttx/config.h>
#include <fcntl.h>
#include <poll.h>
@@ -640,7 +640,7 @@ Sensors::~Sensors()
/* if we have given up, kill it */
if (++i > 50) {
- px4_task_delete(_sensors_task);
+ task_delete(_sensors_task);
break;
}
} while (_sensors_task != -1);
@@ -2235,7 +2235,7 @@ Sensors::start()
ASSERT(_sensors_task == -1);
/* start the task */
- _sensors_task = px4_task_spawn_cmd("sensors_task",
+ _sensors_task = task_spawn_cmd("sensors_task",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
2000,
diff --git a/src/modules/uORB/uORB.cpp b/src/modules/uORB/uORB.cpp
index 0effddb2d..b4f81d429 100644
--- a/src/modules/uORB/uORB.cpp
+++ b/src/modules/uORB/uORB.cpp
@@ -36,7 +36,7 @@
* A lightweight object broker.
*/
-#include <px4_tasks.h>
+#include <nuttx/config.h>
#include <drivers/device/device.h>
@@ -965,7 +965,7 @@ latency_test(orb_id_t T, bool print)
/* test pub / sub latency */
- int pubsub_task = px4_task_spawn_cmd("uorb_latency",
+ int pubsub_task = task_spawn_cmd("uorb_latency",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
1500,
diff --git a/src/modules/uavcan/uavcan_main.cpp b/src/modules/uavcan/uavcan_main.cpp
index 21adcea8a..2d5abf959 100644
--- a/src/modules/uavcan/uavcan_main.cpp
+++ b/src/modules/uavcan/uavcan_main.cpp
@@ -31,7 +31,7 @@
*
****************************************************************************/
-#include <px4_tasks.h>
+#include <nuttx/config.h>
#include <cstdlib>
#include <cstring>
@@ -109,7 +109,7 @@ UavcanNode::~UavcanNode()
/* if we have given up, kill it */
if (--i == 0) {
- px4_task_delete(_task);
+ 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 = px4_task_spawn_cmd("uavcan", SCHED_DEFAULT, SCHED_PRIORITY_ACTUATOR_OUTPUTS, StackSize,
+ _instance->_task = task_spawn_cmd("uavcan", SCHED_DEFAULT, SCHED_PRIORITY_ACTUATOR_OUTPUTS, StackSize,
static_cast<main_t>(run_trampoline), nullptr);
if (_instance->_task < 0) {
diff --git a/src/modules/vtol_att_control/vtol_att_control_main.cpp b/src/modules/vtol_att_control/vtol_att_control_main.cpp
index 20af0978a..defcff8e4 100644
--- a/src/modules/vtol_att_control/vtol_att_control_main.cpp
+++ b/src/modules/vtol_att_control/vtol_att_control_main.cpp
@@ -44,7 +44,7 @@
*
*/
-#include <px4_tasks.h>
+#include <nuttx/config.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
@@ -298,7 +298,7 @@ VtolAttitudeControl::~VtolAttitudeControl()
/* if we have given up, kill it */
if (++i > 50) {
- px4_task_delete(_control_task);
+ task_delete(_control_task);
break;
}
} while (_control_task != -1);
@@ -859,7 +859,7 @@ VtolAttitudeControl::start()
ASSERT(_control_task == -1);
/* start the task */
- _control_task = px4_task_spawn_cmd("vtol_att_control",
+ _control_task = task_spawn_cmd("vtol_att_control",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 10,
2048,