diff --git a/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp b/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp index a1c56aa1f8..f9099cd167 100644 --- a/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp +++ b/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp @@ -202,7 +202,7 @@ int AttitudeEstimatorQ::start() { ASSERT(_control_task == -1); /* start the task */ - _control_task = task_spawn_cmd("attitude_estimator_q", + _control_task = px4_task_spawn_cmd("attitude_estimator_q", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, 2500, diff --git a/src/systemcmds/tests/test_mount.c b/src/systemcmds/tests/test_mount.c index 68052258ef..107d616b6c 100644 --- a/src/systemcmds/tests/test_mount.c +++ b/src/systemcmds/tests/test_mount.c @@ -288,7 +288,7 @@ test_mount(int argc, char *argv[]) fsync(fileno(stdout)); fsync(fileno(stderr)); usleep(50000); - systemreset(false); + px4_systemreset(false); /* never going to get here */ return 0;