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
dc127fe7
Commit
dc127fe7
authored
13 years ago
by
Andrew Tridgell
Browse files
Options
Downloads
Patches
Plain Diff
SITL: ensure we don't run the sitl timer twice
this caused problems with random()
parent
2a011578
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
libraries/Desktop/support/sitl.cpp
+8
-0
8 additions, 0 deletions
libraries/Desktop/support/sitl.cpp
with
8 additions
and
0 deletions
libraries/Desktop/support/sitl.cpp
+
8
−
0
View file @
dc127fe7
...
@@ -223,7 +223,12 @@ static void sitl_simulator_output(void)
...
@@ -223,7 +223,12 @@ static void sitl_simulator_output(void)
static
void
timer_handler
(
int
signum
)
static
void
timer_handler
(
int
signum
)
{
{
static
uint32_t
last_update_count
;
static
uint32_t
last_update_count
;
static
bool
running
;
if
(
running
)
{
return
;
}
running
=
true
;
cli
();
cli
();
#ifndef __CYGWIN__
#ifndef __CYGWIN__
...
@@ -261,11 +266,13 @@ static void timer_handler(int signum)
...
@@ -261,11 +266,13 @@ static void timer_handler(int signum)
if
(
update_count
==
0
)
{
if
(
update_count
==
0
)
{
sitl_update_gps
(
0
,
0
,
0
,
0
,
0
,
false
);
sitl_update_gps
(
0
,
0
,
0
,
0
,
0
,
false
);
sei
();
sei
();
running
=
false
;
return
;
return
;
}
}
if
(
update_count
==
last_update_count
)
{
if
(
update_count
==
last_update_count
)
{
sei
();
sei
();
running
=
false
;
return
;
return
;
}
}
last_update_count
=
update_count
;
last_update_count
=
update_count
;
...
@@ -280,6 +287,7 @@ static void timer_handler(int signum)
...
@@ -280,6 +287,7 @@ static void timer_handler(int signum)
sitl_update_barometer
(
sim_state
.
altitude
);
sitl_update_barometer
(
sim_state
.
altitude
);
sitl_update_compass
(
sim_state
.
rollDeg
,
sim_state
.
pitchDeg
,
sim_state
.
heading
);
sitl_update_compass
(
sim_state
.
rollDeg
,
sim_state
.
pitchDeg
,
sim_state
.
heading
);
sei
();
sei
();
running
=
false
;
}
}
...
...
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