mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_SITL: add simulated frsky support
This commit is contained in:
parent
da2f60ae95
commit
0c8e6f212d
|
@ -295,6 +295,26 @@ int SITL_State::sim_fd(const char *name, const char *arg)
|
|||
}
|
||||
nmea = new SITL::RF_NMEA();
|
||||
return nmea->fd();
|
||||
|
||||
} else if (streq(name, "frsky-d")) {
|
||||
if (frsky_d != nullptr) {
|
||||
AP_HAL::panic("Only one frsky_d at a time");
|
||||
}
|
||||
frsky_d = new SITL::Frsky_D();
|
||||
return frsky_d->fd();
|
||||
// } else if (streq(name, "frsky-SPort")) {
|
||||
// if (frsky_sport != nullptr) {
|
||||
// AP_HAL::panic("Only one frsky_sport at a time");
|
||||
// }
|
||||
// frsky_sport = new SITL::Frsky_SPort();
|
||||
// return frsky_sport->fd();
|
||||
|
||||
// } else if (streq(name, "frsky-SPortPassthrough")) {
|
||||
// if (frsky_sport_passthrough != nullptr) {
|
||||
// AP_HAL::panic("Only one frsky_sport passthrough at a time");
|
||||
// }
|
||||
// frsky_sport = new SITL::Frsky_SPortPassthrough();
|
||||
// return frsky_sportpassthrough->fd();
|
||||
}
|
||||
|
||||
AP_HAL::panic("unknown simulated device: %s", name);
|
||||
|
@ -366,6 +386,11 @@ int SITL_State::sim_fd_write(const char *name)
|
|||
AP_HAL::panic("No nmea created");
|
||||
}
|
||||
return nmea->write_fd();
|
||||
} else if (streq(name, "frsky-d")) {
|
||||
if (frsky_d == nullptr) {
|
||||
AP_HAL::panic("No frsky-d created");
|
||||
}
|
||||
return frsky_d->write_fd();
|
||||
}
|
||||
AP_HAL::panic("unknown simulated device: %s", name);
|
||||
}
|
||||
|
@ -540,6 +565,16 @@ void SITL_State::_fdm_input_local(void)
|
|||
nmea->update(sitl_model->get_range());
|
||||
}
|
||||
|
||||
if (frsky_d != nullptr) {
|
||||
frsky_d->update();
|
||||
}
|
||||
// if (frsky_sport != nullptr) {
|
||||
// frsky_sport->update();
|
||||
// }
|
||||
// if (frsky_sportpassthrough != nullptr) {
|
||||
// frsky_sportpassthrough->update();
|
||||
// }
|
||||
|
||||
if (_sitl) {
|
||||
_sitl->efi_ms.update();
|
||||
}
|
||||
|
|
|
@ -36,6 +36,11 @@
|
|||
#include <SITL/SIM_RF_MaxsonarSerialLV.h>
|
||||
#include <SITL/SIM_RF_Wasp.h>
|
||||
#include <SITL/SIM_RF_NMEA.h>
|
||||
|
||||
#include <SITL/SIM_Frsky_D.h>
|
||||
// #include <SITL/SIM_Frsky_SPort.h>
|
||||
// #include <SITL/SIM_Frsky_SPortPassthrough.h>
|
||||
|
||||
#include <AP_HAL/utility/Socket.h>
|
||||
|
||||
class HAL_SITL;
|
||||
|
@ -262,6 +267,11 @@ private:
|
|||
// simulated NMEA rangefinder:
|
||||
SITL::RF_NMEA *nmea;
|
||||
|
||||
// simulated Frsky devices
|
||||
SITL::Frsky_D *frsky_d;
|
||||
// SITL::Frsky_SPort *frsky_sport;
|
||||
// SITL::Frsky_SPortPassthrough *frsky_sportpassthrough;
|
||||
|
||||
// output socket for flightgear viewing
|
||||
SocketAPM fg_socket{true};
|
||||
|
||||
|
|
|
@ -209,7 +209,7 @@ size_t UARTDriver::write(const uint8_t *buffer, size_t size)
|
|||
if (nwritten == -1 && errno != EAGAIN && _uart_path) {
|
||||
if (_fd_write != -1) {
|
||||
close(_fd_write);
|
||||
_fd_write = 1;
|
||||
_fd_write = -1;
|
||||
}
|
||||
close(_fd);
|
||||
_fd = -1;
|
||||
|
|
Loading…
Reference in New Issue