Skip to content

Commit e92337a

Browse files
RomanLutstronnag
andauthored
SITL: implemented built-in serial receivers support in SITL, implemented FC proxy mode, updated SITL docs (iNavFlight#9365)
* implemented built-in serial receivers support in SITL implemented FC Proxy for SITL update SITL.md * Update SITL.md * Update SITL.md * Update SITL.md * Update SITL.md * [SITL] update POSIX serial functions to support non-standard baud rates * disable xon/hof on serial port (SITL serial_proxy) --------- Co-authored-by: Jonathan Hudson <[email protected]>
1 parent c5d1459 commit e92337a

15 files changed

+1143
-96
lines changed

docs/SITL/SITL.md

+83-59
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,10 @@ Currently supported are
1616

1717
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.
1818

19+
AS SITL is still an inav software, but running on PC, it is possible to use HITL interface for communication.
20+
21+
INAV-X-Plane-HITL plugin https://github.com/RomanLut/INAV-X-Plane-HITL can be used with SITL.
22+
1923
## Sensors
2024
The following sensors are emulated:
2125
- IMU (Gyro, Accelerometer)
@@ -30,13 +34,18 @@ The following sensors are emulated:
3034

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

33-
## Serial ports+
34-
UARTs are replaced by TCP starting with port 5760 ascending. UART 1 port 5760, UART2 5761, ...
35-
By default, UART1 and UART2 are available as MSP connections. Other UARTs will have TCP listeners if they have an INAV function assigned.
36-
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).
37+
## Serial ports
38+
UARTs are replaced by TCP starting with port 5760 ascending. UART1 is mapped to port 5760, UART2 to 5761, etc.
39+
40+
By default, UART1 and UART2 are configured for MSP connections. Other UARTs will have TCP listeners if they have an INAV function assigned.
41+
42+
To connect the Configurator to SITL, select "SITL".
43+
44+
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).
45+
3746
IPv4 and IPv6 are supported, either raw addresses or host-name lookup.
3847

39-
The assignment and status of user UART/TCP connections is displayed on the console.
48+
The assignment and status of used UART/TCP connections is displayed on the console.
4049

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

5362
## Remote control
54-
MSP_RX (TCP/IP) or joystick (via simulator) or serial receiver via USB/Serial interface are supported.
63+
Multiple methods for connecting RC Controllers are available:
64+
- MSP_RX (TCP/IP)
65+
- joystick (via simulator)
66+
- serial receiver via USB to serial converter
67+
- any receiver with proxy flight controller
68+
5569

5670
### MSP_RX
5771

58-
MSP_RX is the default, 18 channels are supported over TCP/IP serial emulation.
72+
MSP_RX is the default, 18 channels are supported over TCP/IP connection.
5973

6074
### Joystick interface
6175
Only 8 channels are supported.
62-
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.
76+
77+
Select "SIM (SITL)" as the receiver and set up a joystick in the simulator.
78+
79+
*Not available with INAV-X-Plane-HITL plugin.*
6380

6481
### Serial Receiver via USB
6582

66-
Connect a serial receiver (e.g. SBUS) to the PC via a UART/USB adapter. Configure the receiver in the Configurator as usual.
83+
- Connect a serial receiver to the PC via a USB-to-serial adapter
84+
- Configure the receiver in the SITL as usual
85+
- While starting SITL from configurator, enable "Serial receiver" option
86+
87+
The SITL offers a built-in option for forwarding the host's serial port to the SITL UART.
88+
89+
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.
6790

68-
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:
6991

70-
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)
71-
If necessary, please download the required runtime environment from https://www.python.org/.
72-
Please use the linked version, which has a smaller buffer, otherwise the control response is relatively slow.
92+
#### Example SBUS:
93+
For this you need a USB-to-serial adapter, receiver with inverter, or receiver which can output inverted SBUS (normal UART).
7394

74-
### Example SBUS:
75-
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.
95+
SBUS protocol is inverted UART.
96+
97+
Receiver's SBUS output should be connected to the USB-to-serial adapter's RX pin (via inverter).
98+
99+
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.
76100

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

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

82105
### Telemetry
106+
In the SITL configuration, enable serial receiver on some port and configure receiver type "Serial", "SBUS".
107+
108+
#### Example CRSF:
109+
110+
On receiver side, CRSF is normal UART.
111+
112+
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).
113+
114+
![SITL-SBUS](assets/serial_receiver_crsf.png)
115+
116+
In the SITL configuration, enable serial receiver on some port and configure receiver type "Serial", "CRSF".
117+
118+
### Proxy Flight controller
119+
120+
The last, but probably the most easiest way to connect receiver to the SITL, is to use any inav/betaflight Flight controler as proxy.
121+
122+
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.
83123

84-
LTM and MAVLink telemetry are supported, either as a discrete function or shared with MSP.
124+
You also can use your plane/quad ( if receiver is powered from USB).
125+
126+
![SITL-SBUS](assets/serial_receiver_proxy.png)
127+
128+
In the SITL configuration, select "Receiver type: SIM" regardles of the kind of receiver used.
85129

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

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

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

137+
*With INAV-X-Plane-HITL plugin, OSD is supported natively.*
138+
94139
## Command line
95140

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

104149
```--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```.
105150

106-
```--sim=[sim]``` Select the simulator. xp = X-Plane, rf = RealFlight. Example: ```--sim=xp```
151+
```--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.
107152

108153
```--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```.
109154

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

166+
```--serialport``` Use serial receiver or proxy FC connected to host's serial port, f.e. ```--serialportCOM5``` or ```--serialportdev/ttyACM3```
167+
168+
```--serialuart``` Map serial receiver to SITL UART, f.e. ```--serialuart=3``` for UART3. Omit if using ```--fcproxy```.
169+
170+
```--baudrate``` Serial receiver baudrate (default: 115200)
171+
172+
```--stopbits=[None|One|Two]``` Serial receiver stopbits (default: One)
173+
174+
```--parity=[Even|None|Odd]``` Serial receiver parity (default: None)
175+
176+
```--fcproxy``` Use inav/betaflight FC as a proxy for serial receiver.
177+
121178
```--help``` Displays help for the command line options.
122179

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

125182
## Running SITL
126183
It is recommended to start the tools in the following order:
127184
1. Simulator, aircraft should be ready for take-off
128-
2. INAV-SITL
185+
2. SITL
129186
3. OSD
130-
4. serial redirect for RC input
131-
132-
## Compile
133-
134-
### Linux and FreeBSD:
135-
Almost like normal, ruby, cmake and make are also required.
136-
With cmake, the option "-DSITL=ON" must be specified.
137-
138-
```
139-
mkdir build_SITL
140-
cd build_SITL
141-
cmake -DSITL=ON ..
142-
make
143-
```
144-
145-
### Windows:
146-
Compile under cygwin, then as in Linux.
147-
Copy cygwin1.dll into the directory, or include cygwin's /bin/ directory in the environment variable PATH.
148-
149-
If the build fails (segfault, possibly out of memory), adding `-DCMAKE_BUILD_TYPE=MinRelSize` to the `cmake` command may help.
150-
151-
#### Build manager
152-
153-
`ninja` may also be used (parallel builds without `-j $(nproc)`):
154-
155-
```
156-
cmake -GNinja -DSITL=ON ..
157-
ninja
158-
```
159-
160-
### Compiler requirements
161187

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

166-
## Supported environments
192+
# #Forwarding serial data for other UART
167193

168-
* Linux on x86_64, ia-32, Aarch64 (e.g. Rpi4), RISCV64 (e.g. VisionFive2)
169-
* Windows on x86_64
170-
* FreeBSD (x86_64 at least).
194+
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```
6.83 KB
Loading
6.94 KB
Loading
6.64 KB
Loading

docs/development/Building SITL.md

+39
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,39 @@
1+
## Building SITL
2+
3+
### Linux and FreeBSD:
4+
Almost like normal, ruby, cmake and make are also required.
5+
With cmake, the option "-DSITL=ON" must be specified.
6+
7+
```
8+
mkdir build_SITL
9+
cd build_SITL
10+
cmake -DSITL=ON ..
11+
make
12+
```
13+
14+
### Windows:
15+
Compile under cygwin, then as in Linux.
16+
Copy cygwin1.dll into the directory, or include cygwin's /bin/ directory in the environment variable PATH.
17+
18+
If the build fails (segfault, possibly out of memory), adding `-DCMAKE_BUILD_TYPE=MinRelSize` to the `cmake` command may help.
19+
20+
#### Build manager
21+
22+
`ninja` may also be used (parallel builds without `-j $(nproc)`):
23+
24+
```
25+
cmake -GNinja -DSITL=ON ..
26+
ninja
27+
```
28+
29+
### Compiler requirements
30+
31+
* Modern GCC. Must be a *real* GCC, macOS faking it with clang will not work. GCC 10 to GCC 13 are known to work.
32+
* Unix sockets networking. Cygwin is required on Windows (vice `winsock`).
33+
* Pthreads
34+
35+
## Supported environments
36+
37+
* Linux on x86_64, ia-32, Aarch64 (e.g. Rpi4), RISCV64 (e.g. VisionFive2)
38+
* Windows on x86_64
39+
* FreeBSD (x86_64 at least).

src/main/drivers/serial_tcp.c

+36-13
Original file line numberDiff line numberDiff line change
@@ -43,6 +43,7 @@
4343

4444
#include "drivers/serial.h"
4545
#include "drivers/serial_tcp.h"
46+
#include "target/SITL/serial_proxy.h"
4647

4748
static const struct serialPortVTable tcpVTable[];
4849
static tcpPort_t tcpPorts[SERIAL_PORT_COUNT];
@@ -118,6 +119,23 @@ static tcpPort_t *tcpReConfigure(tcpPort_t *port, uint32_t id)
118119
return port;
119120
}
120121

122+
void tcpReceiveBytes( tcpPort_t *port, const uint8_t* buffer, ssize_t recvSize ) {
123+
for (ssize_t i = 0; i < recvSize; i++) {
124+
if (port->serialPort.rxCallback) {
125+
port->serialPort.rxCallback((uint16_t)buffer[i], port->serialPort.rxCallbackData);
126+
} else {
127+
pthread_mutex_lock(&port->receiveMutex);
128+
port->serialPort.rxBuffer[port->serialPort.rxBufferHead] = buffer[i];
129+
port->serialPort.rxBufferHead = (port->serialPort.rxBufferHead + 1) % port->serialPort.rxBufferSize;
130+
pthread_mutex_unlock(&port->receiveMutex);
131+
}
132+
}
133+
}
134+
135+
void tcpReceiveBytesEx( int portIndex, const uint8_t* buffer, ssize_t recvSize ) {
136+
tcpReceiveBytes( &tcpPorts[portIndex], buffer, recvSize );
137+
}
138+
121139
int tcpReceive(tcpPort_t *port)
122140
{
123141
char addrbuf[IPADDRESS_PRINT_BUFLEN];
@@ -162,22 +180,12 @@ int tcpReceive(tcpPort_t *port)
162180
return 0;
163181
}
164182

165-
for (ssize_t i = 0; i < recvSize; i++) {
166-
167-
if (port->serialPort.rxCallback) {
168-
port->serialPort.rxCallback((uint16_t)buffer[i], port->serialPort.rxCallbackData);
169-
} else {
170-
pthread_mutex_lock(&port->receiveMutex);
171-
port->serialPort.rxBuffer[port->serialPort.rxBufferHead] = buffer[i];
172-
port->serialPort.rxBufferHead = (port->serialPort.rxBufferHead + 1) % port->serialPort.rxBufferSize;
173-
pthread_mutex_unlock(&port->receiveMutex);
174-
}
175-
}
176-
177183
if (recvSize < 0) {
178184
recvSize = 0;
179185
}
180186

187+
tcpReceiveBytes( port, buffer, recvSize );
188+
181189
return (int)recvSize;
182190
}
183191

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

251+
int getTcpPortIndex(const serialPort_t *instance) {
252+
for (int i = 0; i < SERIAL_PORT_COUNT; i++) {
253+
if ( &(tcpPorts[i].serialPort) == instance) return i;
254+
}
255+
return -1;
256+
}
257+
243258
void tcpWrite(serialPort_t *instance, uint8_t ch)
244259
{
245260
tcpWritBuf(instance, (void*)&ch, 1);
261+
262+
int index = getTcpPortIndex(instance);
263+
if ( !serialFCProxy && serialProxyIsConnected() && (index == (serialUartIndex-1)) ) {
264+
serialProxyWriteData( (unsigned char *)&ch, 1);
265+
}
246266
}
247267

248268
uint32_t tcpTotalRxBytesWaiting(const serialPort_t *instance)
@@ -263,6 +283,10 @@ uint32_t tcpTotalRxBytesWaiting(const serialPort_t *instance)
263283
return count;
264284
}
265285

286+
uint32_t tcpRXBytesFree(int portIndex) {
287+
return tcpPorts[portIndex].serialPort.rxBufferSize - tcpTotalRxBytesWaiting( &tcpPorts[portIndex].serialPort);
288+
}
289+
266290
uint32_t tcpTotalTxBytesFree(const serialPort_t *instance)
267291
{
268292
UNUSED(instance);
@@ -272,7 +296,6 @@ uint32_t tcpTotalTxBytesFree(const serialPort_t *instance)
272296
bool isTcpTransmitBufferEmpty(const serialPort_t *instance)
273297
{
274298
UNUSED(instance);
275-
276299
return true;
277300
}
278301

src/main/drivers/serial_tcp.h

+6-2
Original file line numberDiff line numberDiff line change
@@ -26,6 +26,8 @@
2626
#include <netinet/in.h>
2727
#include <netdb.h>
2828

29+
#include "drivers/serial.h"
30+
2931
#define BASE_IP_ADDRESS 5760
3032
#define TCP_BUFFER_SIZE 2048
3133
#define TCP_MAX_PACKET_SIZE 65535
@@ -50,5 +52,7 @@ typedef struct
5052

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

53-
void tcpSend(tcpPort_t *port);
54-
int tcpReceive(tcpPort_t *port);
55+
extern void tcpSend(tcpPort_t *port);
56+
extern int tcpReceive(tcpPort_t *port);
57+
extern void tcpReceiveBytesEx( int portIndex, const uint8_t* buffer, ssize_t recvSize );
58+
extern uint32_t tcpRXBytesFree(int portIndex);

src/main/fc/fc_init.c

+8
Original file line numberDiff line numberDiff line change
@@ -147,6 +147,10 @@
147147

148148
#include "telemetry/telemetry.h"
149149

150+
#if defined(SITL_BUILD)
151+
#include "target/SITL/serial_proxy.h"
152+
#endif
153+
150154
#ifdef USE_HARDWARE_REVISION_DETECTION
151155
#include "hardware_revision.h"
152156
#endif
@@ -223,6 +227,10 @@ void init(void)
223227
flashDeviceInitialized = flashInit();
224228
#endif
225229

230+
#if defined(SITL_BUILD)
231+
serialProxyInit();
232+
#endif
233+
226234
initEEPROM();
227235
ensureEEPROMContainsValidData();
228236
suspendRxSignal();

0 commit comments

Comments
 (0)