mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
SITL: prevent a fd leak in GPS code
This commit is contained in:
parent
62f1034965
commit
2bc1d4a5ae
@ -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)
|
|||||||
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;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user