forked from Archive/PX4-Autopilot
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:
parent
51a71d54c6
commit
ddb32742eb
|
@ -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) {
|
||||
|
|
|
@ -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,
|
||||
|
|
|
@ -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,
|
||||
|
|
|
@ -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,
|
||||
|
|
|
@ -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,
|
||||
|
|
|
@ -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,
|
||||
|
|
|
@ -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,
|
||||
|
|
|
@ -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,
|
||||
|
|
|
@ -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,
|
||||
|
|
|
@ -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);
|
||||
}
|
||||
|
|
|
@ -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);
|
||||
}
|
||||
|
|
|
@ -41,7 +41,7 @@
|
|||
* @author Thomas Gubler <thomasgubler@gmail.com>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_tasks.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 task_spawn_cmd().
|
||||
* to px4_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 = task_spawn_cmd("attitude_estimator_ekf",
|
||||
attitude_estimator_ekf_task = px4_task_spawn_cmd("attitude_estimator_ekf",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 5,
|
||||
7700,
|
||||
|
|
|
@ -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 <nuttx/config.h>
|
||||
#include <px4_tasks.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 task_spawn_cmd().
|
||||
* to px4_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 = task_spawn_cmd("attitude_estimator_so3",
|
||||
attitude_estimator_so3_task = px4_task_spawn_cmd("attitude_estimator_so3",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 5,
|
||||
14000,
|
||||
|
|
|
@ -40,7 +40,7 @@
|
|||
* @author Julian Oes <joes@student.ethz.ch>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_tasks.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) {
|
||||
task_delete(_main_task);
|
||||
px4_task_delete(_main_task);
|
||||
break;
|
||||
}
|
||||
} while (_main_task != -1);
|
||||
|
@ -225,7 +225,7 @@ BottleDrop::start()
|
|||
ASSERT(_main_task == -1);
|
||||
|
||||
/* start the task */
|
||||
_main_task = task_spawn_cmd("bottle_drop",
|
||||
_main_task = px4_task_spawn_cmd("bottle_drop",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_DEFAULT + 15,
|
||||
1500,
|
||||
|
|
|
@ -42,7 +42,7 @@
|
|||
* @author Anton Babushkin <anton.babushkin@me.com>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_tasks.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 = task_spawn_cmd("commander",
|
||||
daemon_task = px4_task_spawn_cmd("commander",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 40,
|
||||
3400,
|
||||
|
|
|
@ -43,7 +43,7 @@
|
|||
#include "AttitudePositionEstimatorEKF.h"
|
||||
#include "estimator_22states.h"
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_tasks.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) {
|
||||
task_delete(_estimator_task);
|
||||
px4_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 = task_spawn_cmd("ekf_att_pos_estimator",
|
||||
_estimator_task = px4_task_spawn_cmd("ekf_att_pos_estimator",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 40,
|
||||
7500,
|
||||
|
|
|
@ -39,7 +39,7 @@
|
|||
* Fixedwing backside controller using control library
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_tasks.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 = task_spawn_cmd("fixedwing_backside",
|
||||
deamon_task = px4_task_spawn_cmd("fixedwing_backside",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 10,
|
||||
5120,
|
||||
|
|
|
@ -41,7 +41,7 @@
|
|||
*
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_tasks.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) {
|
||||
task_delete(_control_task);
|
||||
px4_task_delete(_control_task);
|
||||
break;
|
||||
}
|
||||
} while (_control_task != -1);
|
||||
|
@ -1117,7 +1117,7 @@ FixedwingAttitudeControl::start()
|
|||
ASSERT(_control_task == -1);
|
||||
|
||||
/* start the task */
|
||||
_control_task = task_spawn_cmd("fw_att_control",
|
||||
_control_task = px4_task_spawn_cmd("fw_att_control",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 5,
|
||||
1600,
|
||||
|
|
|
@ -51,7 +51,7 @@
|
|||
* @author Thomas Gubler <thomasgubler@gmail.com>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_tasks.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) {
|
||||
task_delete(_control_task);
|
||||
px4_task_delete(_control_task);
|
||||
break;
|
||||
}
|
||||
} while (_control_task != -1);
|
||||
|
@ -1621,7 +1621,7 @@ FixedwingPositionControl::start()
|
|||
ASSERT(_control_task == -1);
|
||||
|
||||
/* start the task */
|
||||
_control_task = task_spawn_cmd("fw_pos_control_l1",
|
||||
_control_task = px4_task_spawn_cmd("fw_pos_control_l1",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 5,
|
||||
1600,
|
||||
|
|
|
@ -38,6 +38,7 @@
|
|||
* @author Johan Jansen <jnsn.johan@gmail.com>
|
||||
*/
|
||||
|
||||
#include <px4_tasks.h> //usleep
|
||||
#include <unistd.h> //usleep
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
|
@ -95,7 +96,7 @@ static void land_detector_stop()
|
|||
|
||||
/* if we have given up, kill it */
|
||||
if (++i > 50) {
|
||||
task_delete(_landDetectorTaskID);
|
||||
px4_task_delete(_landDetectorTaskID);
|
||||
break;
|
||||
}
|
||||
} while (land_detector_task->isRunning());
|
||||
|
@ -136,7 +137,7 @@ static int land_detector_start(const char *mode)
|
|||
}
|
||||
|
||||
//Start new thread task
|
||||
_landDetectorTaskID = task_spawn_cmd("land_detector",
|
||||
_landDetectorTaskID = px4_task_spawn_cmd("land_detector",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_DEFAULT,
|
||||
1000,
|
||||
|
|
|
@ -39,7 +39,7 @@
|
|||
* @author Anton Babushkin <anton.babushkin@me.com>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_tasks.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
|
||||
//task_delete(_mavlink_task);
|
||||
//px4_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.
|
||||
task_spawn_cmd(buf,
|
||||
px4_task_spawn_cmd(buf,
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_DEFAULT,
|
||||
2400,
|
||||
|
|
|
@ -53,7 +53,7 @@
|
|||
* If rotation matrix setpoint is invalid it will be generated from Euler angles for compatibility with old position controllers.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_tasks.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) {
|
||||
task_delete(_control_task);
|
||||
px4_task_delete(_control_task);
|
||||
break;
|
||||
}
|
||||
} while (_control_task != -1);
|
||||
|
@ -905,7 +905,7 @@ MulticopterAttitudeControl::start()
|
|||
ASSERT(_control_task == -1);
|
||||
|
||||
/* start the task */
|
||||
_control_task = task_spawn_cmd("mc_att_control",
|
||||
_control_task = px4_task_spawn_cmd("mc_att_control",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 5,
|
||||
1600,
|
||||
|
|
|
@ -36,6 +36,7 @@
|
|||
*
|
||||
* @author Thomas Gubler <thomasgubler@gmail.com>
|
||||
*/
|
||||
#include <px4_tasks.h>
|
||||
#include <string.h>
|
||||
#include <cstdlib>
|
||||
#include <systemlib/err.h>
|
||||
|
@ -68,7 +69,7 @@ int mc_att_control_m_main(int argc, char *argv[])
|
|||
|
||||
task_should_exit = false;
|
||||
|
||||
daemon_task = task_spawn_cmd("mc_att_control_m",
|
||||
daemon_task = px4_task_spawn_cmd("mc_att_control_m",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 5,
|
||||
1900,
|
||||
|
|
|
@ -50,6 +50,7 @@
|
|||
*/
|
||||
|
||||
#include <px4.h>
|
||||
#include <px4_tasks.h>
|
||||
#include <functional>
|
||||
#include <cstdio>
|
||||
#include <stdlib.h>
|
||||
|
@ -384,7 +385,7 @@ MulticopterPositionControl::~MulticopterPositionControl()
|
|||
|
||||
/* if we have given up, kill it */
|
||||
if (++i > 50) {
|
||||
task_delete(_control_task);
|
||||
px4_task_delete(_control_task);
|
||||
break;
|
||||
}
|
||||
} while (_control_task != -1);
|
||||
|
@ -1423,7 +1424,7 @@ MulticopterPositionControl::start()
|
|||
ASSERT(_control_task == -1);
|
||||
|
||||
/* start the task */
|
||||
_control_task = task_spawn_cmd("mc_pos_control",
|
||||
_control_task = px4_task_spawn_cmd("mc_pos_control",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 5,
|
||||
1600,
|
||||
|
|
|
@ -36,6 +36,7 @@
|
|||
*
|
||||
* @author Thomas Gubler <thomasgubler@gmail.com>
|
||||
*/
|
||||
#include <px4_tasks.h>
|
||||
#include <string.h>
|
||||
#include <cstdlib>
|
||||
#include <systemlib/err.h>
|
||||
|
@ -68,7 +69,7 @@ int mc_pos_control_m_main(int argc, char *argv[])
|
|||
|
||||
task_should_exit = false;
|
||||
|
||||
daemon_task = task_spawn_cmd("mc_pos_control_m",
|
||||
daemon_task = px4_task_spawn_cmd("mc_pos_control_m",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 5,
|
||||
2500,
|
||||
|
|
|
@ -43,7 +43,7 @@
|
|||
* @author Thomas Gubler <thomasgubler@gmail.com>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_tasks.h>
|
||||
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
|
@ -174,7 +174,7 @@ Navigator::~Navigator()
|
|||
|
||||
/* if we have given up, kill it */
|
||||
if (++i > 50) {
|
||||
task_delete(_navigator_task);
|
||||
px4_task_delete(_navigator_task);
|
||||
break;
|
||||
}
|
||||
} while (_navigator_task != -1);
|
||||
|
@ -515,7 +515,7 @@ Navigator::start()
|
|||
ASSERT(_navigator_task == -1);
|
||||
|
||||
/* start the task */
|
||||
_navigator_task = task_spawn_cmd("navigator",
|
||||
_navigator_task = px4_task_spawn_cmd("navigator",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_DEFAULT + 20,
|
||||
1800,
|
||||
|
|
|
@ -39,7 +39,7 @@
|
|||
* Segway controller using control library
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_tasks.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 = task_spawn_cmd("segway",
|
||||
deamon_task = px4_task_spawn_cmd("segway",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 10,
|
||||
5120,
|
||||
|
|
|
@ -46,7 +46,7 @@
|
|||
* @author Anton Babushkin <anton@px4.io>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_tasks.h>
|
||||
|
||||
#include <fcntl.h>
|
||||
#include <poll.h>
|
||||
|
@ -640,7 +640,7 @@ Sensors::~Sensors()
|
|||
|
||||
/* if we have given up, kill it */
|
||||
if (++i > 50) {
|
||||
task_delete(_sensors_task);
|
||||
px4_task_delete(_sensors_task);
|
||||
break;
|
||||
}
|
||||
} while (_sensors_task != -1);
|
||||
|
@ -2235,7 +2235,7 @@ Sensors::start()
|
|||
ASSERT(_sensors_task == -1);
|
||||
|
||||
/* start the task */
|
||||
_sensors_task = task_spawn_cmd("sensors_task",
|
||||
_sensors_task = px4_task_spawn_cmd("sensors_task",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 5,
|
||||
2000,
|
||||
|
|
|
@ -36,7 +36,7 @@
|
|||
* A lightweight object broker.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_tasks.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 = task_spawn_cmd("uorb_latency",
|
||||
int pubsub_task = px4_task_spawn_cmd("uorb_latency",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 5,
|
||||
1500,
|
||||
|
|
|
@ -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) {
|
||||
|
|
|
@ -44,7 +44,7 @@
|
|||
*
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <px4_tasks.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) {
|
||||
task_delete(_control_task);
|
||||
px4_task_delete(_control_task);
|
||||
break;
|
||||
}
|
||||
} while (_control_task != -1);
|
||||
|
@ -859,7 +859,7 @@ VtolAttitudeControl::start()
|
|||
ASSERT(_control_task == -1);
|
||||
|
||||
/* start the task */
|
||||
_control_task = task_spawn_cmd("vtol_att_control",
|
||||
_control_task = px4_task_spawn_cmd("vtol_att_control",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 10,
|
||||
2048,
|
||||
|
|
Loading…
Reference in New Issue