mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Copter: run_nav_updates at 50hz on Pixhawk, 25hz on APM2
Based on work by Jon Challinger (see earlier commit)
This commit is contained in:
parent
aa1b0da254
commit
f5fb21b1d7
@ -801,7 +801,7 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = {
|
|||||||
{ arm_motors_check, 40, 1 },
|
{ arm_motors_check, 40, 1 },
|
||||||
{ auto_trim, 40, 14 },
|
{ auto_trim, 40, 14 },
|
||||||
{ update_altitude, 40, 100 },
|
{ update_altitude, 40, 100 },
|
||||||
{ run_nav_updates, 4, 80 },
|
{ run_nav_updates, 8, 80 },
|
||||||
{ update_thr_cruise, 40, 10 },
|
{ update_thr_cruise, 40, 10 },
|
||||||
{ three_hz_loop, 133, 9 },
|
{ three_hz_loop, 133, 9 },
|
||||||
{ compass_accumulate, 8, 42 },
|
{ compass_accumulate, 8, 42 },
|
||||||
@ -869,7 +869,7 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = {
|
|||||||
{ arm_motors_check, 10, 10 },
|
{ arm_motors_check, 10, 10 },
|
||||||
{ auto_trim, 10, 140 },
|
{ auto_trim, 10, 140 },
|
||||||
{ update_altitude, 10, 1000 },
|
{ update_altitude, 10, 1000 },
|
||||||
{ run_nav_updates, 10, 800 },
|
{ run_nav_updates, 4, 800 },
|
||||||
{ update_thr_cruise, 1, 50 },
|
{ update_thr_cruise, 1, 50 },
|
||||||
{ three_hz_loop, 33, 90 },
|
{ three_hz_loop, 33, 90 },
|
||||||
{ compass_accumulate, 2, 420 },
|
{ compass_accumulate, 2, 420 },
|
||||||
|
Loading…
Reference in New Issue
Block a user