AP_HAL_SITL: SITL_State_common: add elrs and pass portnumber in `create_serial_sim`

This commit is contained in:
Iampete1 2024-04-01 21:17:13 +01:00 committed by Andrew Tridgell
parent b0ceaa7610
commit cbd5bcb694
3 changed files with 22 additions and 6 deletions

View File

@ -25,7 +25,7 @@ extern const AP_HAL::HAL& hal;
using namespace HALSITL;
#define streq(a, b) (!strcmp(a, b))
SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const char *arg)
SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const char *arg, const uint8_t portNumber)
{
if (streq(name, "benewake_tf02")) {
if (benewake_tf02 != nullptr) {
@ -314,6 +314,13 @@ SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const
}
gps[x-1] = new SITL::GPS(x-1);
return gps[x-1];
} else if (streq(name, "ELRS")) {
// Only allocate if not done already
// MAVLink serial ports have begin called several times
if (elrs == nullptr) {
elrs = new SITL::ELRS(portNumber, this);
}
return elrs;
}
AP_HAL::panic("unknown simulated device: %s", name);
@ -481,6 +488,10 @@ void SITL_State_Common::sim_update(void)
gps[i]->update();
}
}
if (elrs != nullptr) {
elrs->update();
}
}
/*

View File

@ -53,6 +53,8 @@
#include <SITL/SIM_Loweheiser.h>
#include <SITL/SIM_FETtecOneWireESC.h>
#include <SITL/SIM_ELRS.h>
#include "AP_HAL_SITL.h"
#include "AP_HAL_SITL_Namespace.h"
#include "HAL_SITL_Class.h"
@ -88,7 +90,7 @@ public:
// create a simulated serial device; type of device is given by
// name parameter
SITL::SerialDevice *create_serial_sim(const char *name, const char *arg);
SITL::SerialDevice *create_serial_sim(const char *name, const char *arg, const uint8_t portNumber);
// simulated airspeed, sonar and battery monitor
float sonar_pin_voltage; // pin 0
@ -231,6 +233,9 @@ public:
// simulated GPS devices
SITL::GPS *gps[2]; // constrained by # of parameter sets
// Simulated ELRS radio
SITL::ELRS *elrs;
// returns a voltage between 0V to 5V which should appear as the
// voltage from the sensor
float _sonar_pin_voltage() const;

View File

@ -77,11 +77,11 @@ void UARTDriver::_begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace)
if (strcmp(path, "GPS1") == 0) {
/* gps */
_connected = true;
_sim_serial_device = _sitlState->create_serial_sim("gps:1", "");
_sim_serial_device = _sitlState->create_serial_sim("gps:1", "", _portNumber);
} else if (strcmp(path, "GPS2") == 0) {
/* 2nd gps */
_connected = true;
_sim_serial_device = _sitlState->create_serial_sim("gps:2", "");
_sim_serial_device = _sitlState->create_serial_sim("gps:2", "", _portNumber);
} else {
/* parse type:args:flags string for path.
For example:
@ -109,7 +109,7 @@ void UARTDriver::_begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace)
// add sanity check here that we're doing mavlink on this port?
::printf("SIM-ADSB connection on SERIAL%u\n", _portNumber);
_connected = true;
_sim_serial_device = _sitlState->create_serial_sim("adsb", nullptr);
_sim_serial_device = _sitlState->create_serial_sim("adsb", nullptr, _portNumber);
} else
#endif
if (strcmp(devtype, "tcp") == 0) {
@ -132,7 +132,7 @@ void UARTDriver::_begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace)
if (!_connected) {
::printf("SIM connection %s:%s on SERIAL%u\n", args1, args2, _portNumber);
_connected = true;
_sim_serial_device = _sitlState->create_serial_sim(args1, args2);
_sim_serial_device = _sitlState->create_serial_sim(args1, args2, _portNumber);
}
} else if (strcmp(devtype, "udpclient") == 0) {
// udp client connection