Skip to content
Snippets Groups Projects
Commit 02c5c3ec authored by Andrew Tridgell's avatar Andrew Tridgell
Browse files

HAL_PX4: changed scheduler priorities

put sensor priority above main sketch, to prevent occasional blocking
for sensor data
parent 24826c0c
No related branches found
No related tags found
No related merge requests found
...@@ -149,9 +149,9 @@ static int main_loop(int argc, char **argv) ...@@ -149,9 +149,9 @@ static int main_loop(int argc, char **argv)
this ensures a tight loop waiting on a lower priority driver this ensures a tight loop waiting on a lower priority driver
will eventually give up some time for the driver to run. It will eventually give up some time for the driver to run. It
will only ever be called if a loop() call runs for more than will only ever be called if a loop() call runs for more than
1 second 0.1 second
*/ */
hrt_call_after(&loop_overtime_call, 1000000, (hrt_callout)loop_overtime, NULL); hrt_call_after(&loop_overtime_call, 100000, (hrt_callout)loop_overtime, NULL);
loop(); loop();
......
...@@ -12,8 +12,8 @@ ...@@ -12,8 +12,8 @@
#define PX4_SCHEDULER_MAX_TIMER_PROCS 8 #define PX4_SCHEDULER_MAX_TIMER_PROCS 8
#define APM_MAIN_PRIORITY 200 #define APM_MAIN_PRIORITY 180
#define APM_TIMER_PRIORITY 201 #define APM_TIMER_PRIORITY 181
#define APM_IO_PRIORITY 60 #define APM_IO_PRIORITY 60
#define APM_OVERTIME_PRIORITY 10 #define APM_OVERTIME_PRIORITY 10
#define APM_STARTUP_PRIORITY 10 #define APM_STARTUP_PRIORITY 10
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment