Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

SITL: implemented built-in serial receivers support in SITL, implemented FC proxy mode, updated SITL docs #9365

Merged
merged 11 commits into from
Apr 27, 2024
142 changes: 83 additions & 59 deletions docs/SITL/SITL.md
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,10 @@ Currently supported are

INAV SITL communicates for sensor data and control directly with the corresponding simulator, see the documentation of the individual simulators and the Configurator or the command line options.

AS SITL is still an inav software, but running on PC, it is possible to use HITL interface for communication.

INAV-X-Plane-HITL plugin https://github.com/RomanLut/INAV-X-Plane-HITL can be used with SITL.

## Sensors
The following sensors are emulated:
- IMU (Gyro, Accelerometer)
Expand All @@ -30,13 +34,18 @@ The following sensors are emulated:

Select "FAKE" as type for all mentioned, so that they receive the data from the simulator.

## Serial ports+
UARTs are replaced by TCP starting with port 5760 ascending. UART 1 port 5760, UART2 5761, ...
By default, UART1 and UART2 are available as MSP connections. Other UARTs will have TCP listeners if they have an INAV function assigned.
To connect the Configurator to SITL: Select TCP and connect to ```localhost:5760``` (or ```127.0.0.1:5760``` if your OS doesn't understand `localhost`) (if SITL is running on the same machine).
## Serial ports
UARTs are replaced by TCP starting with port 5760 ascending. UART1 is mapped to port 5760, UART2 to 5761, etc.

By default, UART1 and UART2 are configured for MSP connections. Other UARTs will have TCP listeners if they have an INAV function assigned.

To connect the Configurator to SITL, select "SITL".

Alternativelly, select "TCP" and connect to ```localhost:5760``` (or ```127.0.0.1:5760``` if your OS doesn't understand `localhost`) (if SITL is running on the same machine).

IPv4 and IPv6 are supported, either raw addresses or host-name lookup.

The assignment and status of user UART/TCP connections is displayed on the console.
The assignment and status of used UART/TCP connections is displayed on the console.

```
INAV 6.1.0 SITL
Expand All @@ -51,46 +60,82 @@ INAV 6.1.0 SITL
All other interfaces (I2C, SPI, etc.) are not emulated.

## Remote control
MSP_RX (TCP/IP) or joystick (via simulator) or serial receiver via USB/Serial interface are supported.
Multiple methods for connecting RC Controllers are available:
- MSP_RX (TCP/IP)
- joystick (via simulator)
- serial receiver via USB to serial converter
- any receiver with proxy flight controller


### MSP_RX

MSP_RX is the default, 18 channels are supported over TCP/IP serial emulation.
MSP_RX is the default, 18 channels are supported over TCP/IP connection.

### Joystick interface
Only 8 channels are supported.
Select "SIM (SITL)" as the receiver and set up a joystick in the simulator, details of which can be found in the documentation for the individual simulators.

Select "SIM (SITL)" as the receiver and set up a joystick in the simulator.

*Not available with INAV-X-Plane-HITL plugin.*

### Serial Receiver via USB

Connect a serial receiver (e.g. SBUS) to the PC via a UART/USB adapter. Configure the receiver in the Configurator as usual.
- Connect a serial receiver to the PC via a USB-to-serial adapter
- Configure the receiver in the SITL as usual
- While starting SITL from configurator, enable "Serial receiver" option

The SITL offers a built-in option for forwarding the host's serial port to the SITL UART.

Please note that 100000(SBUS) and 420000(CRSF) are non-standart baud rates which may not be supported by some USB-to-serial adapters. FDTI and CH340 should work. CP2102/9 does not work.

The Configurator offers a built-in option for forwarding the serial data to the SITL TCP port, if SITL is started manually the following option can be used:

The connection can then be established with a programme that forwards the serial data unaltered to TCP, e.g. with the Python script tcp_serial_redirect.py (https://github.com/Scavanger/TCP-Serial-Redirect)
If necessary, please download the required runtime environment from https://www.python.org/.
Please use the linked version, which has a smaller buffer, otherwise the control response is relatively slow.
#### Example SBUS:
For this you need a USB-to-serial adapter, receiver with inverter, or receiver which can output inverted SBUS (normal UART).

### Example SBUS:
For this you need a FT232 module. With FT-Prog (https://ftdichip.com/utilities/) the signals can be inverted: Devices->Scan and Parse, then Hardware Specific -> Invert RS232 Signals -> Invert RXD.
SBUS protocol is inverted UART.

Receiver's SBUS output should be connected to the USB-to-serial adapter's RX pin (via inverter).

With FT-Prog (https://ftdichip.com/utilities/) the signal can be inverted by adapter: Devices->Scan and Parse, then Hardware Specific -> Invert RS232 Signals -> Invert RXD.

![SITL-SBUS-FT232](assets/SITL-SBUS-FT232.png)

For SBUS, the command line arguments of the python script are:
```python tcp_serial_redirect.py --parity E --stopbits 2 -c 127.0.0.1:[INAV-UART-PORT] COMXX 100000```
![SITL-SBUS](assets/serial_receiver_sbus.png)

### Telemetry
In the SITL configuration, enable serial receiver on some port and configure receiver type "Serial", "SBUS".

#### Example CRSF:

On receiver side, CRSF is normal UART.

Connect receiver's RX/TX pins (and GND, 5V of course) to USB-To-Serial adapter's TX/RX pins (RX to TX, TX to RX).

![SITL-SBUS](assets/serial_receiver_crsf.png)

In the SITL configuration, enable serial receiver on some port and configure receiver type "Serial", "CRSF".

### Proxy Flight controller

The last, but probably the most easiest way to connect receiver to the SITL, is to use any inav/betaflight Flight controler as proxy.

Connect receiver of any type to FC and configure FC to the point where channels are correctly updated in the "Receiver" tab. Inav and Betaflight are supported.

LTM and MAVLink telemetry are supported, either as a discrete function or shared with MSP.
You also can use your plane/quad ( if receiver is powered from USB).

![SITL-SBUS](assets/serial_receiver_proxy.png)

In the SITL configuration, select "Receiver type: SIM" regardles of the kind of receiver used.

RX Telemetry via a return channel through the receiver is not yet supported by SITL.

## OSD
For the OSD the program INAV-Sim-OSD is available: https://github.com/Scavanger/INAV-SIM-OSD.
For this, activate MSP-Displayport on a UART/TCP port and connect to the corresponding port.

Note: INAV-Sim-OSD only works if the simulator is in window mode.

*With INAV-X-Plane-HITL plugin, OSD is supported natively.*

## Command line

The command line options are only necessary if the SITL executable is started by hand.
Expand All @@ -103,7 +148,7 @@ If SITL is started without command line options, only a serial MSP / CLI connect

```--path``` Path and file name to config file. If not present, eeprom.bin in the current directory is used. Example: ```C:\INAV_SITL\flying-wing.bin```, ```/home/user/sitl-eeproms/test-eeprom.bin```.

```--sim=[sim]``` Select the simulator. xp = X-Plane, rf = RealFlight. Example: ```--sim=xp```
```--sim=[sim]``` Select the simulator. xp = X-Plane, rf = RealFlight. Example: ```--sim=xp```. If not specified, configurator-only mode is started. Omit for usage with INAV-X-Plane-HITL plugin.

```--simip=[ip]``` Hostname or IP address of the simulator, if you specify a simulator with "--sim" and omit this option IPv4 localhost (`127.0.0.1`) will be used. Example: ```--simip=172.65.21.15```, ```--simip acme-sims.org```, ```--sim ::1```.

Expand All @@ -118,53 +163,32 @@ To assign motor1 to virtual receiver channel 1, servo 1 to channel 2, and servo2
```--chanmap:M01-01,S01-02,S02-03```
Please also read the documentation of the individual simulators.

```--serialport``` Use serial receiver or proxy FC connected to host's serial port, f.e. ```--serialportCOM5``` or ```--serialportdev/ttyACM3```

```--serialuart``` Map serial receiver to SITL UART, f.e. ```--serialuart=3``` for UART3. Omit if using ```--fcproxy```.

```--baudrate``` Serial receiver baudrate (default: 115200)

```--stopbits=[None|One|Two]``` Serial receiver stopbits (default: One)

```--parity=[Even|None|Odd]``` Serial receiver parity (default: None)

```--fcproxy``` Use inav/betaflight FC as a proxy for serial receiver.

```--help``` Displays help for the command line options.

For options that take an argument, either form `--flag=value` or `--flag value` may be used.

## Running SITL
It is recommended to start the tools in the following order:
1. Simulator, aircraft should be ready for take-off
2. INAV-SITL
2. SITL
3. OSD
4. serial redirect for RC input

## Compile

### Linux and FreeBSD:
Almost like normal, ruby, cmake and make are also required.
With cmake, the option "-DSITL=ON" must be specified.

```
mkdir build_SITL
cd build_SITL
cmake -DSITL=ON ..
make
```

### Windows:
Compile under cygwin, then as in Linux.
Copy cygwin1.dll into the directory, or include cygwin's /bin/ directory in the environment variable PATH.

If the build fails (segfault, possibly out of memory), adding `-DCMAKE_BUILD_TYPE=MinRelSize` to the `cmake` command may help.

#### Build manager

`ninja` may also be used (parallel builds without `-j $(nproc)`):

```
cmake -GNinja -DSITL=ON ..
ninja
```

### Compiler requirements

* Modern GCC. Must be a *real* GCC, macOS faking it with clang will not work. GCC 10 to GCC 13 are known to work.
* Unix sockets networking. Cygwin is required on Windows (vice `winsock`).
* Pthreads
For INav-X-Plane-HITL plugin:
1. SITL (Run in configurator-only mode)
2. X-Plane

## Supported environments
# #Forwarding serial data for other UART

* Linux on x86_64, ia-32, Aarch64 (e.g. Rpi4), RISCV64 (e.g. VisionFive2)
* Windows on x86_64
* FreeBSD (x86_64 at least).
Other UARTs can then be mapped to host's serial port using external tool, which can be found in directories ```inav-configurator\resources\sitl\linux\Ser2TCP```, ```inav-configurator\resources\sitl\windows\Ser2TCP.exe```
Binary file added docs/SITL/assets/serial_receiver_crsf.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added docs/SITL/assets/serial_receiver_proxy.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added docs/SITL/assets/serial_receiver_sbus.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
39 changes: 39 additions & 0 deletions docs/development/Building SITL.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
## Building SITL

### Linux and FreeBSD:
Almost like normal, ruby, cmake and make are also required.
With cmake, the option "-DSITL=ON" must be specified.

```
mkdir build_SITL
cd build_SITL
cmake -DSITL=ON ..
make
```

### Windows:
Compile under cygwin, then as in Linux.
Copy cygwin1.dll into the directory, or include cygwin's /bin/ directory in the environment variable PATH.

If the build fails (segfault, possibly out of memory), adding `-DCMAKE_BUILD_TYPE=MinRelSize` to the `cmake` command may help.

#### Build manager

`ninja` may also be used (parallel builds without `-j $(nproc)`):

```
cmake -GNinja -DSITL=ON ..
ninja
```

### Compiler requirements

* Modern GCC. Must be a *real* GCC, macOS faking it with clang will not work. GCC 10 to GCC 13 are known to work.
* Unix sockets networking. Cygwin is required on Windows (vice `winsock`).
* Pthreads

## Supported environments

* Linux on x86_64, ia-32, Aarch64 (e.g. Rpi4), RISCV64 (e.g. VisionFive2)
* Windows on x86_64
* FreeBSD (x86_64 at least).
49 changes: 36 additions & 13 deletions src/main/drivers/serial_tcp.c
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@

#include "drivers/serial.h"
#include "drivers/serial_tcp.h"
#include "target/SITL/serial_proxy.h"

static const struct serialPortVTable tcpVTable[];
static tcpPort_t tcpPorts[SERIAL_PORT_COUNT];
Expand Down Expand Up @@ -118,6 +119,23 @@ static tcpPort_t *tcpReConfigure(tcpPort_t *port, uint32_t id)
return port;
}

void tcpReceiveBytes( tcpPort_t *port, const uint8_t* buffer, ssize_t recvSize ) {
for (ssize_t i = 0; i < recvSize; i++) {
if (port->serialPort.rxCallback) {
port->serialPort.rxCallback((uint16_t)buffer[i], port->serialPort.rxCallbackData);
} else {
pthread_mutex_lock(&port->receiveMutex);
port->serialPort.rxBuffer[port->serialPort.rxBufferHead] = buffer[i];
port->serialPort.rxBufferHead = (port->serialPort.rxBufferHead + 1) % port->serialPort.rxBufferSize;
pthread_mutex_unlock(&port->receiveMutex);
}
}
}

void tcpReceiveBytesEx( int portIndex, const uint8_t* buffer, ssize_t recvSize ) {
tcpReceiveBytes( &tcpPorts[portIndex], buffer, recvSize );
}

int tcpReceive(tcpPort_t *port)
{
char addrbuf[IPADDRESS_PRINT_BUFLEN];
Expand Down Expand Up @@ -162,22 +180,12 @@ int tcpReceive(tcpPort_t *port)
return 0;
}

for (ssize_t i = 0; i < recvSize; i++) {

if (port->serialPort.rxCallback) {
port->serialPort.rxCallback((uint16_t)buffer[i], port->serialPort.rxCallbackData);
} else {
pthread_mutex_lock(&port->receiveMutex);
port->serialPort.rxBuffer[port->serialPort.rxBufferHead] = buffer[i];
port->serialPort.rxBufferHead = (port->serialPort.rxBufferHead + 1) % port->serialPort.rxBufferSize;
pthread_mutex_unlock(&port->receiveMutex);
}
}

if (recvSize < 0) {
recvSize = 0;
}

tcpReceiveBytes( port, buffer, recvSize );

return (int)recvSize;
}

Expand Down Expand Up @@ -240,9 +248,21 @@ void tcpWritBuf(serialPort_t *instance, const void *data, int count)
send(port->clientSocketFd, data, count, 0);
}

int getTcpPortIndex(const serialPort_t *instance) {
for (int i = 0; i < SERIAL_PORT_COUNT; i++) {
if ( &(tcpPorts[i].serialPort) == instance) return i;
}
return -1;
}

void tcpWrite(serialPort_t *instance, uint8_t ch)
{
tcpWritBuf(instance, (void*)&ch, 1);

int index = getTcpPortIndex(instance);
if ( !serialFCProxy && serialProxyIsConnected() && (index == (serialUartIndex-1)) ) {
serialProxyWriteData( (unsigned char *)&ch, 1);
}
}

uint32_t tcpTotalRxBytesWaiting(const serialPort_t *instance)
Expand All @@ -263,6 +283,10 @@ uint32_t tcpTotalRxBytesWaiting(const serialPort_t *instance)
return count;
}

uint32_t tcpRXBytesFree(int portIndex) {
return tcpPorts[portIndex].serialPort.rxBufferSize - tcpTotalRxBytesWaiting( &tcpPorts[portIndex].serialPort);
}

uint32_t tcpTotalTxBytesFree(const serialPort_t *instance)
{
UNUSED(instance);
Expand All @@ -272,7 +296,6 @@ uint32_t tcpTotalTxBytesFree(const serialPort_t *instance)
bool isTcpTransmitBufferEmpty(const serialPort_t *instance)
{
UNUSED(instance);

return true;
}

Expand Down
8 changes: 6 additions & 2 deletions src/main/drivers/serial_tcp.h
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,8 @@
#include <netinet/in.h>
#include <netdb.h>

#include "drivers/serial.h"

#define BASE_IP_ADDRESS 5760
#define TCP_BUFFER_SIZE 2048
#define TCP_MAX_PACKET_SIZE 65535
Expand All @@ -50,5 +52,7 @@ typedef struct

serialPort_t *tcpOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback, void *rxCallbackData, uint32_t baudRate, portMode_t mode, portOptions_t options);

void tcpSend(tcpPort_t *port);
int tcpReceive(tcpPort_t *port);
extern void tcpSend(tcpPort_t *port);
extern int tcpReceive(tcpPort_t *port);
extern void tcpReceiveBytesEx( int portIndex, const uint8_t* buffer, ssize_t recvSize );
extern uint32_t tcpRXBytesFree(int portIndex);
8 changes: 8 additions & 0 deletions src/main/fc/fc_init.c
Original file line number Diff line number Diff line change
Expand Up @@ -147,6 +147,10 @@

#include "telemetry/telemetry.h"

#if defined(SITL_BUILD)
#include "target/SITL/serial_proxy.h"
#endif

#ifdef USE_HARDWARE_REVISION_DETECTION
#include "hardware_revision.h"
#endif
Expand Down Expand Up @@ -223,6 +227,10 @@ void init(void)
flashDeviceInitialized = flashInit();
#endif

#if defined(SITL_BUILD)
serialProxyInit();
#endif

initEEPROM();
ensureEEPROMContainsValidData();
suspendRxSignal();
Expand Down
Loading
Loading