mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
HAL_PX4: changed scheduler priorities
put sensor priority above main sketch, to prevent occasional blocking for sensor data
This commit is contained in:
parent
24826c0c74
commit
02c5c3ec4a
@ -149,9 +149,9 @@ static int main_loop(int argc, char **argv)
|
||||
this ensures a tight loop waiting on a lower priority driver
|
||||
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
|
||||
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();
|
||||
|
||||
|
@ -12,8 +12,8 @@
|
||||
|
||||
#define PX4_SCHEDULER_MAX_TIMER_PROCS 8
|
||||
|
||||
#define APM_MAIN_PRIORITY 200
|
||||
#define APM_TIMER_PRIORITY 201
|
||||
#define APM_MAIN_PRIORITY 180
|
||||
#define APM_TIMER_PRIORITY 181
|
||||
#define APM_IO_PRIORITY 60
|
||||
#define APM_OVERTIME_PRIORITY 10
|
||||
#define APM_STARTUP_PRIORITY 10
|
||||
|
Loading…
Reference in New Issue
Block a user