forked from Archive/PX4-Autopilot
Rename our 'task_spawn' to 'task_spawn_cmd' since NuttX now has its own version of task_spawn that's different.
This commit is contained in:
parent
198df9c82e
commit
23a6234235
|
@ -114,7 +114,7 @@ int ardrone_interface_main(int argc, char *argv[])
|
|||
}
|
||||
|
||||
thread_should_exit = false;
|
||||
ardrone_interface_task = task_spawn("ardrone_interface",
|
||||
ardrone_interface_task = task_spawn_cmd("ardrone_interface",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 15,
|
||||
2048,
|
||||
|
|
|
@ -224,7 +224,7 @@ HIL::init()
|
|||
// gpio_reset();
|
||||
|
||||
/* start the HIL interface task */
|
||||
_task = task_spawn("fmuhil",
|
||||
_task = task_spawn_cmd("fmuhil",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_DEFAULT,
|
||||
2048,
|
||||
|
|
|
@ -272,7 +272,7 @@ int hott_telemetry_main(int argc, char *argv[])
|
|||
}
|
||||
|
||||
thread_should_exit = false;
|
||||
deamon_task = task_spawn("hott_telemetry",
|
||||
deamon_task = task_spawn_cmd("hott_telemetry",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 40,
|
||||
2048,
|
||||
|
|
|
@ -109,7 +109,7 @@ int md25_main(int argc, char *argv[])
|
|||
}
|
||||
|
||||
thread_should_exit = false;
|
||||
deamon_task = task_spawn("md25",
|
||||
deamon_task = task_spawn_cmd("md25",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 10,
|
||||
2048,
|
||||
|
|
|
@ -313,7 +313,7 @@ MK::init(unsigned motors)
|
|||
gpio_reset();
|
||||
|
||||
/* start the IO interface task */
|
||||
_task = task_spawn("mkblctrl",
|
||||
_task = task_spawn_cmd("mkblctrl",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 20,
|
||||
2048,
|
||||
|
|
|
@ -239,7 +239,7 @@ PX4FMU::init()
|
|||
gpio_reset();
|
||||
|
||||
/* start the IO interface task */
|
||||
_task = task_spawn("fmuservo",
|
||||
_task = task_spawn_cmd("fmuservo",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_DEFAULT,
|
||||
2048,
|
||||
|
|
|
@ -528,7 +528,7 @@ int ex_fixedwing_control_main(int argc, char *argv[])
|
|||
}
|
||||
|
||||
thread_should_exit = false;
|
||||
deamon_task = task_spawn("ex_fixedwing_control",
|
||||
deamon_task = task_spawn_cmd("ex_fixedwing_control",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 20,
|
||||
2048,
|
||||
|
|
|
@ -91,7 +91,7 @@ int px4_deamon_app_main(int argc, char *argv[])
|
|||
}
|
||||
|
||||
thread_should_exit = false;
|
||||
deamon_task = task_spawn("deamon",
|
||||
deamon_task = task_spawn_cmd("deamon",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_DEFAULT,
|
||||
4096,
|
||||
|
|
|
@ -100,7 +100,7 @@ int att_pos_estimator_ekf_main(int argc, char *argv[])
|
|||
}
|
||||
|
||||
thread_should_exit = false;
|
||||
deamon_task = task_spawn("kalman_demo",
|
||||
deamon_task = task_spawn_cmd("kalman_demo",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 5,
|
||||
4096,
|
||||
|
|
|
@ -123,7 +123,7 @@ int attitude_estimator_ekf_main(int argc, char *argv[])
|
|||
}
|
||||
|
||||
thread_should_exit = false;
|
||||
attitude_estimator_ekf_task = task_spawn("attitude_estimator_ekf",
|
||||
attitude_estimator_ekf_task = task_spawn_cmd("attitude_estimator_ekf",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 5,
|
||||
12400,
|
||||
|
|
|
@ -1200,7 +1200,7 @@ int commander_main(int argc, char *argv[])
|
|||
}
|
||||
|
||||
thread_should_exit = false;
|
||||
daemon_task = task_spawn("commander",
|
||||
daemon_task = task_spawn_cmd("commander",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 40,
|
||||
3000,
|
||||
|
|
|
@ -336,7 +336,7 @@ int fixedwing_att_control_main(int argc, char *argv[])
|
|||
}
|
||||
|
||||
thread_should_exit = false;
|
||||
deamon_task = task_spawn("fixedwing_att_control",
|
||||
deamon_task = task_spawn_cmd("fixedwing_att_control",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 20,
|
||||
2048,
|
||||
|
|
|
@ -107,7 +107,7 @@ int fixedwing_backside_main(int argc, char *argv[])
|
|||
}
|
||||
|
||||
thread_should_exit = false;
|
||||
deamon_task = task_spawn("control_demo",
|
||||
deamon_task = task_spawn_cmd("control_demo",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 10,
|
||||
5120,
|
||||
|
|
|
@ -448,7 +448,7 @@ int fixedwing_pos_control_main(int argc, char *argv[])
|
|||
}
|
||||
|
||||
thread_should_exit = false;
|
||||
deamon_task = task_spawn("fixedwing_pos_control",
|
||||
deamon_task = task_spawn_cmd("fixedwing_pos_control",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 20,
|
||||
2048,
|
||||
|
|
|
@ -787,7 +787,7 @@ int mavlink_main(int argc, char *argv[])
|
|||
errx(0, "mavlink already running\n");
|
||||
|
||||
thread_should_exit = false;
|
||||
mavlink_task = task_spawn("mavlink",
|
||||
mavlink_task = task_spawn_cmd("mavlink",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_DEFAULT,
|
||||
2048,
|
||||
|
|
|
@ -495,7 +495,7 @@ int mavlink_onboard_main(int argc, char *argv[])
|
|||
errx(0, "mavlink already running\n");
|
||||
|
||||
thread_should_exit = false;
|
||||
mavlink_task = task_spawn("mavlink_onboard",
|
||||
mavlink_task = task_spawn_cmd("mavlink_onboard",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_DEFAULT,
|
||||
2048,
|
||||
|
|
|
@ -466,7 +466,7 @@ int multirotor_att_control_main(int argc, char *argv[])
|
|||
if (!strcmp(argv[1 + optioncount], "start")) {
|
||||
|
||||
thread_should_exit = false;
|
||||
mc_task = task_spawn("multirotor_att_control",
|
||||
mc_task = task_spawn_cmd("multirotor_att_control",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 15,
|
||||
2048,
|
||||
|
|
|
@ -94,7 +94,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().
|
||||
* to task_spawn_cmd().
|
||||
*/
|
||||
int multirotor_pos_control_main(int argc, char *argv[])
|
||||
{
|
||||
|
@ -110,7 +110,7 @@ int multirotor_pos_control_main(int argc, char *argv[])
|
|||
}
|
||||
|
||||
thread_should_exit = false;
|
||||
deamon_task = task_spawn("multirotor pos control",
|
||||
deamon_task = task_spawn_cmd("multirotor pos control",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 60,
|
||||
4096,
|
||||
|
|
|
@ -123,7 +123,7 @@ int position_estimator_mc_main(int argc, char *argv[])
|
|||
}
|
||||
|
||||
thread_should_exit = false;
|
||||
position_estimator_mc_task = task_spawn("position_estimator_mc",
|
||||
position_estimator_mc_task = task_spawn_cmd("position_estimator_mc",
|
||||
SCHED_RR,
|
||||
SCHED_PRIORITY_MAX - 5,
|
||||
4096,
|
||||
|
|
|
@ -161,7 +161,7 @@ bool logging_enabled = true;
|
|||
* Makefile does only apply to this management task.
|
||||
*
|
||||
* The actual stack size should be set in the call
|
||||
* to task_spawn().
|
||||
* to task_spawn_cmd().
|
||||
*/
|
||||
int sdlog_main(int argc, char *argv[])
|
||||
{
|
||||
|
@ -177,7 +177,7 @@ int sdlog_main(int argc, char *argv[])
|
|||
}
|
||||
|
||||
thread_should_exit = false;
|
||||
deamon_task = task_spawn("sdlog",
|
||||
deamon_task = task_spawn_cmd("sdlog",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_DEFAULT - 30,
|
||||
4096,
|
||||
|
|
|
@ -1445,7 +1445,7 @@ Sensors::start()
|
|||
ASSERT(_sensors_task == -1);
|
||||
|
||||
/* start the task */
|
||||
_sensors_task = task_spawn("sensors_task",
|
||||
_sensors_task = task_spawn_cmd("sensors_task",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 5,
|
||||
2048,
|
||||
|
|
|
@ -65,7 +65,7 @@ static void kill_task(FAR struct tcb_s *tcb, FAR void *arg)
|
|||
kill(tcb->pid, SIGUSR1);
|
||||
}
|
||||
|
||||
int task_spawn(const char *name, int scheduler, int priority, int stack_size, main_t entry, const char *argv[])
|
||||
int task_spawn_cmd(const char *name, int scheduler, int priority, int stack_size, main_t entry, const char *argv[])
|
||||
{
|
||||
int pid;
|
||||
|
||||
|
|
|
@ -58,7 +58,7 @@ __EXPORT void killall(void);
|
|||
#endif
|
||||
|
||||
/** Starts a task and performs any specific accounting, scheduler setup, etc. */
|
||||
__EXPORT int task_spawn(const char *name,
|
||||
__EXPORT int task_spawn_cmd(const char *name,
|
||||
int priority,
|
||||
int scheduler,
|
||||
int stack_size,
|
||||
|
|
Loading…
Reference in New Issue