Skip to content
GitLab
Explore
Sign in
Primary navigation
Search or go to…
Project
F
Firmware
Manage
Activity
Members
Labels
Plan
Issues
Issue boards
Milestones
Wiki
Code
Merge requests
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Snippets
Build
Pipelines
Jobs
Pipeline schedules
Artifacts
Deploy
Releases
Package registry
Model registry
Operate
Environments
Terraform modules
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
Terms and privacy
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
Alberto Ruiz Garcia
Firmware
Commits
3bb479f7
Commit
3bb479f7
authored
8 years ago
by
Beat Küng
Committed by
Lorenz Meier
8 years ago
Browse files
Options
Downloads
Patches
Plain Diff
ulog mavlink: use the px4_sem calls (needed for OSX)
parent
7c40c8df
No related branches found
Branches containing commit
No related tags found
Tags containing commit
No related merge requests found
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
src/modules/mavlink/mavlink_ulog.cpp
+2
-2
2 additions, 2 deletions
src/modules/mavlink/mavlink_ulog.cpp
src/modules/mavlink/mavlink_ulog.h
+3
-3
3 additions, 3 deletions
src/modules/mavlink/mavlink_ulog.h
with
5 additions
and
5 deletions
src/modules/mavlink/mavlink_ulog.cpp
+
2
−
2
View file @
3bb479f7
...
...
@@ -45,7 +45,7 @@
bool
MavlinkULog
::
_init
=
false
;
MavlinkULog
*
MavlinkULog
::
_instance
=
nullptr
;
sem_t
MavlinkULog
::
_lock
;
px4_
sem_t
MavlinkULog
::
_lock
;
const
float
MavlinkULog
::
_rate_calculation_delta_t
=
0.1
f
;
...
...
@@ -185,7 +185,7 @@ void MavlinkULog::initialize()
if
(
_init
)
{
return
;
}
sem_init
(
&
_lock
,
1
,
1
);
px4_
sem_init
(
&
_lock
,
1
,
1
);
_init
=
true
;
}
...
...
This diff is collapsed.
Click to expand it.
src/modules/mavlink/mavlink_ulog.h
+
3
−
3
View file @
3bb479f7
...
...
@@ -105,17 +105,17 @@ private:
static
void
lock
()
{
do
{}
while
(
sem_wait
(
&
_lock
)
!=
0
);
do
{}
while
(
px4_
sem_wait
(
&
_lock
)
!=
0
);
}
static
void
unlock
()
{
sem_post
(
&
_lock
);
px4_
sem_post
(
&
_lock
);
}
void
publish_ack
(
uint16_t
sequence
);
static
sem_t
_lock
;
static
px4_
sem_t
_lock
;
static
bool
_init
;
static
MavlinkULog
*
_instance
;
static
const
float
_rate_calculation_delta_t
;
///< rate update interval
...
...
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