AP_HAL_SITL: make SITL::ADSB a SITL::SerialDevice
This commit is contained in:
parent
c99a49eeb9
commit
cdccc67fb8
@ -168,15 +168,6 @@ void SITL_State::_fdm_input_step(void)
|
||||
if (_sitl != nullptr) {
|
||||
_update_airspeed(_sitl->state.airspeed);
|
||||
_update_rangefinder(_sitl->state.range);
|
||||
|
||||
if (_sitl->adsb_plane_count >= 0 &&
|
||||
adsb == nullptr) {
|
||||
adsb = new SITL::ADSB(_sitl->state, sitl_model->get_home(), get_instance());
|
||||
} else if (_sitl->adsb_plane_count == -1 &&
|
||||
adsb != nullptr) {
|
||||
delete adsb;
|
||||
adsb = nullptr;
|
||||
}
|
||||
}
|
||||
|
||||
// trigger all APM timers.
|
||||
@ -220,6 +211,14 @@ SITL::SerialDevice *SITL_State::create_serial_sim(const char *name, const char *
|
||||
}
|
||||
vicon = new SITL::Vicon();
|
||||
return vicon;
|
||||
} else if (streq(name, "adsb")) {
|
||||
// ADSB is a stand-out as it is the only serial device which
|
||||
// will cope with begin() being called multiple times on a
|
||||
// serial port
|
||||
if (adsb == nullptr) {
|
||||
adsb = new SITL::ADSB();
|
||||
}
|
||||
return adsb;
|
||||
} else if (streq(name, "benewake_tf02")) {
|
||||
if (benewake_tf02 != nullptr) {
|
||||
AP_HAL::panic("Only one benewake_tf02 at a time");
|
||||
@ -534,7 +533,7 @@ void SITL_State::_fdm_input_local(void)
|
||||
gimbal->update();
|
||||
}
|
||||
if (adsb != nullptr) {
|
||||
adsb->update();
|
||||
adsb->update(*sitl_model);
|
||||
}
|
||||
if (vicon != nullptr) {
|
||||
Quaternion attitude;
|
||||
|
@ -89,6 +89,16 @@ void UARTDriver::begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace)
|
||||
char *devtype = strtok_r(s, ":", &saveptr);
|
||||
char *args1 = strtok_r(nullptr, ":", &saveptr);
|
||||
char *args2 = strtok_r(nullptr, ":", &saveptr);
|
||||
#if !defined(HAL_BUILD_AP_PERIPH)
|
||||
if (_portNumber == 2 && AP::sitl()->adsb_plane_count >= 0) {
|
||||
// this is ordinarily port 5762. The ADSB simulation assumed
|
||||
// this port, so if enabled we assume we'll be doing ADSB...
|
||||
// add sanity check here that we're doing mavlink on this port?
|
||||
::printf("SIM-ADSB connection on port %u\n", _portNumber);
|
||||
_connected = true;
|
||||
_sim_serial_device = _sitlState->create_serial_sim("adsb", nullptr);
|
||||
} else
|
||||
#endif
|
||||
if (strcmp(devtype, "tcp") == 0) {
|
||||
uint16_t port = atoi(args1);
|
||||
bool wait = (args2 && strcmp(args2, "wait") == 0);
|
||||
|
Loading…
Reference in New Issue
Block a user