Browse Source

AP_HAL_SITL: load SIM_AIS

gps-1.3.1
Iampete1 4 years ago committed by Randy Mackay
parent
commit
6deacda180
  1. 15
      libraries/AP_HAL_SITL/SITL_State.cpp
  2. 4
      libraries/AP_HAL_SITL/SITL_State.h

15
libraries/AP_HAL_SITL/SITL_State.cpp

@ -382,6 +382,12 @@ int SITL_State::sim_fd(const char *name, const char *arg) @@ -382,6 +382,12 @@ int SITL_State::sim_fd(const char *name, const char *arg)
}
vectornav = new SITL::VectorNav();
return vectornav->fd();
} else if (streq(name, "AIS")) {
if (ais != nullptr) {
AP_HAL::panic("Only one AIS at a time");
}
ais = new SITL::AIS();
return ais->fd();
}
AP_HAL::panic("unknown simulated device: %s", name);
@ -502,6 +508,11 @@ int SITL_State::sim_fd_write(const char *name) @@ -502,6 +508,11 @@ int SITL_State::sim_fd_write(const char *name)
AP_HAL::panic("No VectorNav created");
}
return vectornav->write_fd();
} else if (streq(name, "AIS")) {
if (ais == nullptr) {
AP_HAL::panic("No AIS created");
}
return ais->write_fd();
}
AP_HAL::panic("unknown simulated device: %s", name);
}
@ -723,6 +734,10 @@ void SITL_State::_fdm_input_local(void) @@ -723,6 +734,10 @@ void SITL_State::_fdm_input_local(void)
vectornav->update();
}
if (ais != nullptr) {
ais->update();
}
if (_sitl) {
_sitl->efi_ms.update();
}

4
libraries/AP_HAL_SITL/SITL_State.h

@ -44,6 +44,7 @@ @@ -44,6 +44,7 @@
#include <SITL/SIM_RF_MAVLink.h>
#include <SITL/SIM_RF_GYUS42v2.h>
#include <SITL/SIM_VectorNav.h>
#include <SITL/SIM_AIS.h>
#include <SITL/SIM_Frsky_D.h>
#include <SITL/SIM_CRSF.h>
@ -312,6 +313,9 @@ private: @@ -312,6 +313,9 @@ private:
// Ride along instances via JSON SITL backend
SITL::JSON_Master ride_along;
// simulated AIS stream
SITL::AIS *ais;
// output socket for flightgear viewing
SocketAPM fg_socket{true};

Loading…
Cancel
Save