ESP32 icon indicating copy to clipboard operation
ESP32 copied to clipboard

Can not connect to INAV Configurator (MSP) to the FC

Open TByte007 opened this issue 1 year ago • 4 comments

I can connect to the FC with INAV Config via the same FC cables/port with USB-TTL I see that there is something coming on pins 17,16 of ESP32 when INAV Config is trying to connect (with the same USB-TTL and a terminal program). I can send and receive MSP with my own ESP8266 on the same port/cables of the FC and the same speed (115200). I tested for continuity of the cables and it is ok/connected.

But when I try to use the ESP32 Bridge INAV Config connects then timeouts "No configuration received within 10 seconds, communication failed". UART Serial is set to "MSP/LTM" and 11520. I don't know what "MSP & LTM to same port" means exactly but I left it default.

What could be going on ?

PS: It seems like the UART is receiving data:

UART received bytes 48 bytes

PS1: Very very rarely by setting it to "Transparent" I get a response 'MultiWii API version received - 2.5.0' but then a timeout again:

2024-02-27 @ 00:46:08 -- MSP connection successfully opened with ID: 7 2024-02-27 @ 00:46:11 -- MultiWii API version received - 2.5.0 2024-02-27 @ 00:46:18 -- No configuration received within 10 seconds, communication failed 2024-02-27 @ 00:46:18 -- MSP connection successfully closed

Most of the time there is not even that line with the version.

PS2: The smaller the "Transparent packet size" more I receive. This is what I got from size 16:

2024-02-27 @ 02:41:59 -- MSP connection successfully opened with ID: 14 2024-02-27 @ 02:41:59 -- MultiWii API version received - 2.5.0 2024-02-27 @ 02:42:02 -- Flight controller info, identifier: INAV, version: 7.0.0 2024-02-27 @ 02:42:08 -- Running firmware released on: Dec 5 2023 10:53:05 2024-02-27 @ 02:42:09 -- No configuration received within 10 seconds, communication failed 2024-02-27 @ 02:42:09 -- MSP connection successfully closed

TByte007 avatar Feb 26 '24 23:02 TByte007

I found the problem The line https://github.com/DroneBridge/ESP32/blob/71422b15ac54e336c97a02bb82c952d59e15cc88/main/db_esp32_control.c#L161 have to be switched with the line https://github.com/DroneBridge/ESP32/blob/71422b15ac54e336c97a02bb82c952d59e15cc88/main/db_esp32_control.c#L162 Otherwise you are always sending 0 bytes !

TByte007 avatar Feb 28 '24 03:02 TByte007

Oh no, on the first look that seems pretty obvious to me as well. I'll fix it in the next release! Thank you!

P.S: MSP & LTM to same port means that all messages received via the UART (no matter if LTM or MSP) are forwarded to the same TCP/UDP port. If set to no, the streams are split and sent to different ports.

seeul8er avatar Feb 28 '24 07:02 seeul8er

P.S: MSP & LTM to same port means that all messages received via the UART (no matter if LTM or MSP) are forwarded to the same TCP/UDP port. If set to no, the streams are split and sent to different ports.

Btw I don't see 1607 nor 1604 even being open UDP or TCP

I (2485) TCP_SERVER_SETUP: Opened TCP server on port 5760 I (2485) DB_CONTROL: Opened UDP socket on port 14550 I (2495) DB_CONTROL: Started control module I (2615) DB_HTTP_REST: Starting HTTP Server I (2625) TCP_SERVER_SETUP: Opened TCP server on port 1603

These are the only ports being open.

TByte007 avatar Mar 01 '24 11:03 TByte007

The data should be sent to different ports on your computer. The ESP is opening only one socket.

seeul8er avatar Mar 01 '24 12:03 seeul8er

Hopefully fixed with v1.5

seeul8er avatar Mar 08 '24 17:03 seeul8er