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
2bc1d4a5
Commit
2bc1d4a5
authored
12 years ago
by
Andrew Tridgell
Browse files
Options
Downloads
Patches
Plain Diff
SITL: prevent a fd leak in GPS code
parent
62f10349
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_gps.cpp
+7
-3
7 additions, 3 deletions
libraries/Desktop/support/sitl_gps.cpp
with
7 additions
and
3 deletions
libraries/Desktop/support/sitl_gps.cpp
+
7
−
3
View file @
2bc1d4a5
...
@@ -37,7 +37,7 @@ static uint8_t gps_delay;
...
@@ -37,7 +37,7 @@ static uint8_t gps_delay;
// state of GPS emulation
// state of GPS emulation
static
struct
{
static
struct
{
/* pipe emulating UBLOX GPS serial stream */
/* pipe emulating UBLOX GPS serial stream */
int
gps_fd
;
int
gps_fd
,
client_fd
;
uint32_t
last_update
;
// milliseconds
uint32_t
last_update
;
// milliseconds
}
gps_state
;
}
gps_state
;
...
@@ -55,12 +55,16 @@ ssize_t sitl_gps_read(int fd, void *buf, size_t count)
...
@@ -55,12 +55,16 @@ ssize_t sitl_gps_read(int fd, void *buf, size_t count)
int
sitl_gps_pipe
(
void
)
int
sitl_gps_pipe
(
void
)
{
{
int
fd
[
2
];
int
fd
[
2
];
if
(
gps_state
.
client_fd
!=
0
)
{
return
gps_state
.
client_fd
;
}
pipe
(
fd
);
pipe
(
fd
);
gps_state
.
gps_fd
=
fd
[
1
];
gps_state
.
gps_fd
=
fd
[
1
];
gps_state
.
client_fd
=
fd
[
0
];
gps_state
.
last_update
=
millis
();
gps_state
.
last_update
=
millis
();
set_nonblocking
(
gps_state
.
gps_fd
);
set_nonblocking
(
gps_state
.
gps_fd
);
set_nonblocking
(
fd
[
0
]);
set_nonblocking
(
fd
[
0
]);
return
fd
[
0
]
;
return
gps_state
.
client_fd
;
}
}
...
...
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