mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_SITL: add ability to simulate more than 2 GPSs
This commit is contained in:
parent
42b3bec595
commit
4b679dfb1a
|
@ -304,13 +304,9 @@ SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const
|
||||||
return ais;
|
return ais;
|
||||||
#endif
|
#endif
|
||||||
} else if (strncmp(name, "gps", 3) == 0) {
|
} else if (strncmp(name, "gps", 3) == 0) {
|
||||||
const char *p = strchr(name, ':');
|
uint8_t x = atoi(arg);
|
||||||
if (p == nullptr) {
|
|
||||||
AP_HAL::panic("Need a GPS number (e.g. sim:gps:1)");
|
|
||||||
}
|
|
||||||
uint8_t x = atoi(p+1);
|
|
||||||
if (x <= 0 || x > ARRAY_SIZE(gps)) {
|
if (x <= 0 || x > ARRAY_SIZE(gps)) {
|
||||||
AP_HAL::panic("Bad GPS number %u", x);
|
AP_HAL::panic("Bad GPS number %u (%s)", x, arg);
|
||||||
}
|
}
|
||||||
gps[x-1] = NEW_NOTHROW SITL::GPS(x-1);
|
gps[x-1] = NEW_NOTHROW SITL::GPS(x-1);
|
||||||
return gps[x-1];
|
return gps[x-1];
|
||||||
|
|
|
@ -231,7 +231,7 @@ public:
|
||||||
const char *defaults_path = HAL_PARAM_DEFAULTS_PATH;
|
const char *defaults_path = HAL_PARAM_DEFAULTS_PATH;
|
||||||
|
|
||||||
// simulated GPS devices
|
// simulated GPS devices
|
||||||
SITL::GPS *gps[2]; // constrained by # of parameter sets
|
SITL::GPS *gps[AP_SIM_MAX_GPS_SENSORS]; // constrained by # of parameter sets
|
||||||
|
|
||||||
// Simulated ELRS radio
|
// Simulated ELRS radio
|
||||||
SITL::ELRS *elrs;
|
SITL::ELRS *elrs;
|
||||||
|
|
|
@ -77,11 +77,11 @@ void UARTDriver::_begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace)
|
||||||
if (strcmp(path, "GPS1") == 0) {
|
if (strcmp(path, "GPS1") == 0) {
|
||||||
/* gps */
|
/* gps */
|
||||||
_connected = true;
|
_connected = true;
|
||||||
_sim_serial_device = _sitlState->create_serial_sim("gps:1", "", _portNumber);
|
_sim_serial_device = _sitlState->create_serial_sim("gps", "1", _portNumber);
|
||||||
} else if (strcmp(path, "GPS2") == 0) {
|
} else if (strcmp(path, "GPS2") == 0) {
|
||||||
/* 2nd gps */
|
/* 2nd gps */
|
||||||
_connected = true;
|
_connected = true;
|
||||||
_sim_serial_device = _sitlState->create_serial_sim("gps:2", "", _portNumber);
|
_sim_serial_device = _sitlState->create_serial_sim("gps", "2", _portNumber);
|
||||||
} else {
|
} else {
|
||||||
/* parse type:args:flags string for path.
|
/* parse type:args:flags string for path.
|
||||||
For example:
|
For example:
|
||||||
|
|
Loading…
Reference in New Issue