mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
SITL: removed GPS FIFO
This commit is contained in:
parent
c151d9bc3d
commit
791d0acefe
@ -20,15 +20,6 @@
|
||||
#include <AP_Common/NMEA.h>
|
||||
#include <AP_HAL/utility/sparse-endian.h>
|
||||
|
||||
// simulated CAN GPS devices get fed from our SITL estimates:
|
||||
#if HAL_SIM_GPS_EXTERNAL_FIFO_ENABLED
|
||||
#include <sys/types.h>
|
||||
#include <sys/stat.h>
|
||||
#include <errno.h>
|
||||
#include <AP_HAL_SITL/AP_HAL_SITL.h>
|
||||
extern const HAL_SITL& hal_sitl;
|
||||
#endif
|
||||
|
||||
// the number of GPS leap seconds - copied from AP_GPS.h
|
||||
#define GPS_LEAPSECONDS_MILLIS 18000ULL
|
||||
|
||||
@ -77,22 +68,6 @@ GPS::GPS(uint8_t _instance) :
|
||||
SerialDevice(8192, 2048),
|
||||
instance{_instance}
|
||||
{
|
||||
|
||||
#if HAL_SIM_GPS_EXTERNAL_FIFO_ENABLED
|
||||
const uint8_t num_gps = 2;
|
||||
// pipe number is SITL instance number (e.g. -I argument to
|
||||
// sim_vehicle.py) times the max number of GPSs + the gps instance
|
||||
// number:
|
||||
const uint8_t num = num_gps * hal_sitl.get_instance() + instance;
|
||||
if (asprintf(&_gps_fifo, "/tmp/gps_fifo%u", (unsigned)num) == -1) { // FIXME - needs to work with simulated periph-gps
|
||||
AP_BoardConfig::allocation_error("gps_fifo filepath");
|
||||
}
|
||||
if (mkfifo(_gps_fifo, 0666) < 0) {
|
||||
if (errno != EEXIST) {
|
||||
printf("MKFIFO failed with %m\n");
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
uint32_t GPS::device_baud() const
|
||||
@ -116,15 +91,6 @@ ssize_t GPS::write_to_autopilot(const char *p, size_t size) const
|
||||
return -1;
|
||||
}
|
||||
|
||||
#if HAL_SIM_GPS_EXTERNAL_FIFO_ENABLED
|
||||
// also write to external fifo
|
||||
int fd = open(_gps_fifo, O_WRONLY | O_NONBLOCK);
|
||||
if (fd >= 0) {
|
||||
UNUSED_RESULT(write(fd, p, size));
|
||||
close(fd);
|
||||
}
|
||||
#endif
|
||||
|
||||
const float byteloss = _sitl->gps_byteloss[instance];
|
||||
|
||||
// shortcut if we're not doing byteloss:
|
||||
|
@ -26,15 +26,11 @@ param set SERIAL5_PROTOCOL 5
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef HAL_SIM_GPS_ENABLED
|
||||
#define HAL_SIM_GPS_ENABLED (AP_SIM_ENABLED && !defined(HAL_BUILD_AP_PERIPH))
|
||||
#define HAL_SIM_GPS_ENABLED AP_SIM_ENABLED
|
||||
#endif
|
||||
|
||||
#if HAL_SIM_GPS_ENABLED
|
||||
|
||||
#ifndef HAL_SIM_GPS_EXTERNAL_FIFO_ENABLED
|
||||
#define HAL_SIM_GPS_EXTERNAL_FIFO_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL) && !defined(CYGWIN_BUILD)
|
||||
#endif
|
||||
|
||||
#ifndef AP_SIM_GPS_FILE_ENABLED
|
||||
// really need to use AP_FileSystem for this.
|
||||
#define AP_SIM_GPS_FILE_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX)
|
||||
@ -246,11 +242,6 @@ private:
|
||||
// last 20 samples, allowing for up to 20 samples of delay
|
||||
GPS_Data _gps_history[20];
|
||||
|
||||
#if HAL_SIM_GPS_EXTERNAL_FIFO_ENABLED
|
||||
// this will be allocated if needed:
|
||||
char *_gps_fifo;
|
||||
#endif
|
||||
|
||||
bool _gps_has_basestation_position;
|
||||
GPS_Data _gps_basestation_data;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user