Skip to content
GitLab
Explore
Sign in
Register
Primary navigation
Search or go to…
Project
A
Ardupilot
Manage
Activity
Members
Labels
Plan
Issues
0
Issue boards
Milestones
Wiki
Code
Merge requests
0
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Snippets
Build
Pipelines
Jobs
Pipeline schedules
Artifacts
Deploy
Releases
Model registry
Operate
Environments
Monitor
Incidents
Analyze
Value stream analytics
Contributor analytics
CI/CD analytics
Repository analytics
Model experiments
Help
Help
Support
GitLab documentation
Compare GitLab plans
Community forum
Contribute to GitLab
Provide feedback
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
OpenSource
Ardupilot
Commits
75788396
Commit
75788396
authored
11 years ago
by
Andrew Tridgell
Browse files
Options
Downloads
Patches
Plain Diff
Rover: split up GPS update into 10Hz and 50Hz parts
parent
a96840e1
No related branches found
No related tags found
No related merge requests found
Changes
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
APMrover2/APMrover2.pde
+9
-4
9 additions, 4 deletions
APMrover2/APMrover2.pde
with
9 additions
and
4 deletions
APMrover2/APMrover2.pde
+
9
−
4
View file @
75788396
...
@@ -553,9 +553,10 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = {
...
@@ -553,9 +553,10 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = {
{
read_radio
,
1
,
1000
},
{
read_radio
,
1
,
1000
},
{
ahrs_update
,
1
,
6400
},
{
ahrs_update
,
1
,
6400
},
{
read_sonars
,
1
,
2000
},
{
read_sonars
,
1
,
2000
},
{
update_current_mode
,
1
,
1000
},
{
update_current_mode
,
1
,
1500
},
{
set_servos
,
1
,
1000
},
{
set_servos
,
1
,
1500
},
{
update_GPS
,
5
,
2500
},
{
update_GPS_50Hz
,
1
,
2500
},
{
update_GPS_10Hz
,
5
,
2500
},
{
navigate
,
5
,
1600
},
{
navigate
,
5
,
1600
},
{
update_compass
,
5
,
2000
},
{
update_compass
,
5
,
2000
},
{
update_commands
,
5
,
1000
},
{
update_commands
,
5
,
1000
},
...
@@ -803,7 +804,7 @@ static void one_second_loop(void)
...
@@ -803,7 +804,7 @@ static void one_second_loop(void)
}
}
}
}
static
void
update_GPS
(
void
)
static
void
update_GPS
_50Hz
(
void
)
{
{
static
uint32_t
last_gps_reading
;
static
uint32_t
last_gps_reading
;
g_gps
->
update
();
g_gps
->
update
();
...
@@ -814,7 +815,11 @@ static void update_GPS(void)
...
@@ -814,7 +815,11 @@ static void update_GPS(void)
DataFlash
.
Log_Write_GPS
(
g_gps
,
current_loc
.
alt
);
DataFlash
.
Log_Write_GPS
(
g_gps
,
current_loc
.
alt
);
}
}
}
}
}
static
void
update_GPS_10Hz
(
void
)
{
have_position
=
ahrs
.
get_projected_position
(
current_loc
);
have_position
=
ahrs
.
get_projected_position
(
current_loc
);
if
(
g_gps
->
new_data
&&
g_gps
->
status
()
>=
GPS
::
GPS_OK_FIX_3D
)
{
if
(
g_gps
->
new_data
&&
g_gps
->
status
()
>=
GPS
::
GPS_OK_FIX_3D
)
{
...
...
This diff is collapsed.
Click to expand it.
Preview
0%
Loading
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Save comment
Cancel
Please
register
or
sign in
to comment