forked from Archive/PX4-Autopilot
EKF: Push up stack size as the max frame size is already 3.4K
This commit is contained in:
parent
06f5e242d1
commit
766cb71635
|
@ -1122,7 +1122,7 @@ int AttitudePositionEstimatorEKF::start()
|
|||
_estimator_task = px4_task_spawn_cmd("ekf_att_pos_estimator",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 20,
|
||||
3900,
|
||||
4600,
|
||||
(px4_main_t)&AttitudePositionEstimatorEKF::task_main_trampoline,
|
||||
nullptr);
|
||||
|
||||
|
|
Loading…
Reference in New Issue