Browse Source

Rename our 'task_spawn' to 'task_spawn_cmd' since NuttX now has its own version of task_spawn that's different.

sbg
px4dev 12 years ago
parent
commit
23a6234235
  1. 2
      src/drivers/ardrone_interface/ardrone_interface.c
  2. 2
      src/drivers/hil/hil.cpp
  3. 2
      src/drivers/hott_telemetry/hott_telemetry_main.c
  4. 2
      src/drivers/md25/md25_main.cpp
  5. 2
      src/drivers/mkblctrl/mkblctrl.cpp
  6. 2
      src/drivers/px4fmu/fmu.cpp
  7. 2
      src/examples/fixedwing_control/main.c
  8. 2
      src/examples/px4_daemon_app/px4_daemon_app.c
  9. 2
      src/modules/att_pos_estimator_ekf/kalman_main.cpp
  10. 2
      src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
  11. 2
      src/modules/commander/commander.c
  12. 2
      src/modules/fixedwing_att_control/fixedwing_att_control_main.c
  13. 2
      src/modules/fixedwing_backside/fixedwing_backside_main.cpp
  14. 2
      src/modules/fixedwing_pos_control/fixedwing_pos_control_main.c
  15. 2
      src/modules/mavlink/mavlink.c
  16. 2
      src/modules/mavlink_onboard/mavlink.c
  17. 2
      src/modules/multirotor_att_control/multirotor_att_control_main.c
  18. 4
      src/modules/multirotor_pos_control/multirotor_pos_control.c
  19. 2
      src/modules/position_estimator_mc/position_estimator_mc_main.c
  20. 4
      src/modules/sdlog/sdlog.c
  21. 2
      src/modules/sensors/sensors.cpp
  22. 2
      src/modules/systemlib/systemlib.c
  23. 2
      src/modules/systemlib/systemlib.h

2
src/drivers/ardrone_interface/ardrone_interface.c

@ -114,7 +114,7 @@ int ardrone_interface_main(int argc, char *argv[]) @@ -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,

2
src/drivers/hil/hil.cpp

@ -224,7 +224,7 @@ HIL::init() @@ -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,

2
src/drivers/hott_telemetry/hott_telemetry_main.c

@ -272,7 +272,7 @@ int hott_telemetry_main(int argc, char *argv[]) @@ -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,

2
src/drivers/md25/md25_main.cpp

@ -109,7 +109,7 @@ int md25_main(int argc, char *argv[]) @@ -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,

2
src/drivers/mkblctrl/mkblctrl.cpp

@ -313,7 +313,7 @@ MK::init(unsigned motors) @@ -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,

2
src/drivers/px4fmu/fmu.cpp

@ -239,7 +239,7 @@ PX4FMU::init() @@ -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,

2
src/examples/fixedwing_control/main.c

@ -528,7 +528,7 @@ int ex_fixedwing_control_main(int argc, char *argv[]) @@ -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,

2
src/examples/px4_daemon_app/px4_daemon_app.c

@ -91,7 +91,7 @@ int px4_deamon_app_main(int argc, char *argv[]) @@ -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,

2
src/modules/att_pos_estimator_ekf/kalman_main.cpp

@ -100,7 +100,7 @@ int att_pos_estimator_ekf_main(int argc, char *argv[]) @@ -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,

2
src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp

@ -123,7 +123,7 @@ int attitude_estimator_ekf_main(int argc, char *argv[]) @@ -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,

2
src/modules/commander/commander.c

@ -1200,7 +1200,7 @@ int commander_main(int argc, char *argv[]) @@ -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,

2
src/modules/fixedwing_att_control/fixedwing_att_control_main.c

@ -336,7 +336,7 @@ int fixedwing_att_control_main(int argc, char *argv[]) @@ -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,

2
src/modules/fixedwing_backside/fixedwing_backside_main.cpp

@ -107,7 +107,7 @@ int fixedwing_backside_main(int argc, char *argv[]) @@ -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,

2
src/modules/fixedwing_pos_control/fixedwing_pos_control_main.c

@ -448,7 +448,7 @@ int fixedwing_pos_control_main(int argc, char *argv[]) @@ -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,

2
src/modules/mavlink/mavlink.c

@ -787,7 +787,7 @@ int mavlink_main(int argc, char *argv[]) @@ -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,

2
src/modules/mavlink_onboard/mavlink.c

@ -495,7 +495,7 @@ int mavlink_onboard_main(int argc, char *argv[]) @@ -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,

2
src/modules/multirotor_att_control/multirotor_att_control_main.c

@ -466,7 +466,7 @@ int multirotor_att_control_main(int argc, char *argv[]) @@ -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,

4
src/modules/multirotor_pos_control/multirotor_pos_control.c

@ -94,7 +94,7 @@ usage(const char *reason) @@ -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[]) @@ -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,

2
src/modules/position_estimator_mc/position_estimator_mc_main.c

@ -123,7 +123,7 @@ int position_estimator_mc_main(int argc, char *argv[]) @@ -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,

4
src/modules/sdlog/sdlog.c

@ -161,7 +161,7 @@ bool logging_enabled = true; @@ -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[]) @@ -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,

2
src/modules/sensors/sensors.cpp

@ -1445,7 +1445,7 @@ Sensors::start() @@ -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,

2
src/modules/systemlib/systemlib.c

@ -65,7 +65,7 @@ static void kill_task(FAR struct tcb_s *tcb, FAR void *arg) @@ -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;

2
src/modules/systemlib/systemlib.h

@ -58,7 +58,7 @@ __EXPORT void killall(void); @@ -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…
Cancel
Save