Removed extra abstracton layer in systemlib

The calls to task_spawn_cmd, kill_all, and systemreset  were wrappers
around the px4_{task_spawn_cmd|kill_all|systemreset} implementations.

Removed the wrappers and changed all calls to the px4_ equivalents.

NuttX specific code was moved into px4_tasks.h

Signed-off-by: Mark Charlebois <charlebm@gmail.com>
This commit is contained in:
Mark Charlebois 2015-05-06 14:43:11 -07:00
parent 3654aec3a5
commit c5237f7f6f
38 changed files with 55 additions and 65 deletions

View File

@ -121,7 +121,7 @@ int ardrone_interface_main(int argc, char *argv[])
}
thread_should_exit = false;
ardrone_interface_task = task_spawn_cmd("ardrone_interface",
ardrone_interface_task = px4_task_spawn_cmd("ardrone_interface",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 15,
1100,

View File

@ -216,7 +216,7 @@ int frsky_telemetry_main(int argc, char *argv[])
errx(0, "frsky_telemetry already running");
thread_should_exit = false;
frsky_task = task_spawn_cmd("frsky_telemetry",
frsky_task = px4_task_spawn_cmd("frsky_telemetry",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
2000,

View File

@ -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) {

View File

@ -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,

View File

@ -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,

View File

@ -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,

View File

@ -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,

View File

@ -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,

View File

@ -854,7 +854,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,

View File

@ -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,

View File

@ -414,7 +414,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_px4_task_spawn_cmd().
*/
int ex_fixedwing_control_main(int argc, char *argv[])
{
@ -431,7 +431,7 @@ int ex_fixedwing_control_main(int argc, char *argv[])
}
thread_should_exit = false;
deamon_task = task_spawn_cmd("ex_fixedwing_control",
deamon_task = px4_px4_task_spawn_cmd("ex_fixedwing_control",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 20,
2048,

View File

@ -95,7 +95,7 @@ static void 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_px4_task_spawn_cmd().
*/
int flow_position_estimator_main(int argc, char *argv[])
{
@ -111,7 +111,7 @@ int flow_position_estimator_main(int argc, char *argv[])
}
thread_should_exit = false;
daemon_task = task_spawn_cmd("flow_position_estimator",
daemon_task = px4_px4_task_spawn_cmd("flow_position_estimator",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
4000,

View File

@ -87,7 +87,7 @@ static void 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_px4_task_spawn_cmd().
*/
int matlab_csv_serial_main(int argc, char *argv[])
{
@ -103,7 +103,7 @@ int matlab_csv_serial_main(int argc, char *argv[])
}
thread_should_exit = false;
daemon_task = task_spawn_cmd("matlab_csv_serial",
daemon_task = px4_px4_task_spawn_cmd("matlab_csv_serial",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
2000,

View File

@ -68,7 +68,7 @@ int publisher_main(int argc, char *argv[])
task_should_exit = false;
daemon_task = task_spawn_cmd("publisher",
daemon_task = px4_task_spawn_cmd("publisher",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
2000,

View File

@ -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_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_px4_task_spawn_cmd("rover_steering_control",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 20,
2048,

View File

@ -68,7 +68,7 @@ int subscriber_main(int argc, char *argv[])
task_should_exit = false;
daemon_task = task_spawn_cmd("subscriber",
daemon_task = px4_task_spawn_cmd("subscriber",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
2000,

View File

@ -113,7 +113,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,

View File

@ -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_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_px4_task_spawn_cmd("attitude_estimator_so3",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
14000,

View File

@ -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,

View File

@ -269,7 +269,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,
@ -2652,13 +2652,13 @@ void *commander_low_prio_loop(void *arg)
answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
usleep(100000);
/* reboot */
systemreset(false);
px4_systemreset(false);
} else if (((int)(cmd.param1)) == 3) {
answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
usleep(100000);
/* reboot to bootloader */
systemreset(true);
px4_systemreset(true);
} else {
answer_command(cmd, VEHICLE_CMD_RESULT_DENIED);

View File

@ -1038,7 +1038,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,

View File

@ -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,

View File

@ -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,

View File

@ -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,

View File

@ -136,7 +136,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,

View File

@ -906,7 +906,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,
1500,

View File

@ -68,7 +68,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,

View File

@ -1423,7 +1423,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,
1500,

View File

@ -68,7 +68,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,

View File

@ -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,
1700,

View File

@ -153,7 +153,7 @@ int position_estimator_inav_main(int argc, char *argv[])
}
thread_should_exit = false;
position_estimator_inav_task = task_spawn_cmd("position_estimator_inav",
position_estimator_inav_task = px4_task_spawn_cmd("position_estimator_inav",
SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, 5000,
position_estimator_inav_thread_main,
(argv) ? (char * const *) &argv[2] : (char * const *) NULL);

View File

@ -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,

View File

@ -2252,7 +2252,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,

View File

@ -42,7 +42,6 @@ SRCS = err.c \
cpuload.c \
getopt_long.c \
pid/pid.c \
systemlib.c \
airspeed.c \
system_params.c \
mavlink_log.c \

View File

@ -42,31 +42,12 @@
#include <float.h>
#include <stdint.h>
#include <sched.h>
// OS specific settings defined in px4_tasks.h
#include <px4_tasks.h>
__BEGIN_DECLS
/** Reboots the board */
__EXPORT void systemreset(bool to_bootloader) noreturn_function;
/** Sends SIGUSR1 to all processes */
__EXPORT void killall(void);
/** Default scheduler type */
#if CONFIG_RR_INTERVAL > 0
# define SCHED_DEFAULT SCHED_RR
#else
# define SCHED_DEFAULT SCHED_FIFO
#endif
/** Starts a task and performs any specific accounting, scheduler setup, etc. */
__EXPORT int task_spawn_cmd(const char *name,
int priority,
int scheduler,
int stack_size,
px4_main_t entry,
char * const argv[]);
enum MULT_PORTS {
MULT_0_US2_RXTX = 0,
MULT_1_US2_FLOW,

View File

@ -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) {

View File

@ -861,7 +861,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,

View File

@ -43,16 +43,26 @@
#include <stdbool.h>
#ifdef __PX4_ROS
#error "PX4 tasks not supported in ROS"
#elif defined(__PX4_NUTTX)
typedef int px4_task_t;
/** Default scheduler type */
#if CONFIG_RR_INTERVAL > 0
# define SCHED_DEFAULT SCHED_RR
#else
# define SCHED_DEFAULT SCHED_FIFO
#endif
#define px4_task_exit(x) _exit(x)
#elif defined(__PX4_POSIX) || defined(__PX4_QURT)
#include <pthread.h>
#include <sched.h>
/** Default scheduler type */
#define SCHED_DEFAULT SCHED_FIFO
#ifdef __PX4_LINUX
#define SCHED_PRIORITY_MAX sched_get_priority_max(SCHED_FIFO)