Skip to content
GitLab
Explore
Sign in
Register
Primary navigation
Search or go to…
Project
B
Baitboat
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
Baitboat
Commits
f2e160a5
Commit
f2e160a5
authored
12 years ago
by
Andrew Tridgell
Browse files
Options
Downloads
Patches
Plain Diff
AP_Baro: removed _sync_access check
this isn't needed as the common variables are already protected by cli()/sei()
parent
1b793bf3
No related branches found
Branches containing commit
No related tags found
Tags containing commit
No related merge requests found
Changes
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
libraries/AP_Baro/AP_Baro_MS5611.cpp
+0
-5
0 additions, 5 deletions
libraries/AP_Baro/AP_Baro_MS5611.cpp
with
0 additions
and
5 deletions
libraries/AP_Baro/AP_Baro_MS5611.cpp
+
0
−
5
View file @
f2e160a5
...
...
@@ -58,7 +58,6 @@ uint8_t volatile AP_Baro_MS5611::_d1_count;
uint8_t
volatile
AP_Baro_MS5611
::
_d2_count
;
uint8_t
AP_Baro_MS5611
::
_state
;
uint32_t
AP_Baro_MS5611
::
_timer
;
bool
AP_Baro_MS5611
::
_sync_access
;
bool
volatile
AP_Baro_MS5611
::
_updated
;
uint8_t
AP_Baro_MS5611
::
_spi_read
(
uint8_t
reg
)
...
...
@@ -160,8 +159,6 @@ bool AP_Baro_MS5611::init( AP_PeriodicProcess *scheduler )
// temperature does not change so quickly...
void
AP_Baro_MS5611
::
_update
(
uint32_t
tnow
)
{
if
(
_sync_access
)
return
;
// Throttle read rate to 100hz maximum.
// note we use 9500us here not 10000us
// the read rate will end up at exactly 100hz because the Periodic Timer fires at 1khz
...
...
@@ -206,7 +203,6 @@ void AP_Baro_MS5611::_update(uint32_t tnow)
uint8_t
AP_Baro_MS5611
::
read
()
{
_sync_access
=
true
;
bool
updated
=
_updated
;
if
(
updated
)
{
uint32_t
sD1
,
sD2
;
...
...
@@ -230,7 +226,6 @@ uint8_t AP_Baro_MS5611::read()
_raw_press
=
D1
;
_raw_temp
=
D2
;
}
_sync_access
=
false
;
_calculate
();
if
(
updated
)
{
_last_update
=
millis
();
...
...
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