Unable to establish TCP connection with PX4 SITL from X-Plane plugin

Hello,

I am developing an X-Plane plugin that communicates with the PX4 Software In The Loop (SITL) simulator using a TCP connection. However, I am encountering an issue where the connection fails without any specific error message.

Here’s the relevant code snippet from my plugin:

1void ConnectionManager::connectToSITL(const std::string& sitlIp) {
2    if (connected) return;
3
4    ConnectionManager::sockfd = socket(AF_INET, SOCK_STREAM, 0);
5    if (ConnectionManager::sockfd < 0) {
6        XPLMDebugString("px4xplane: Error opening socket\n");
7        return;
8    }
9
10    sockaddr_in serv_addr{};
11    serv_addr.sin_family = AF_INET;
12    serv_addr.sin_port = htons(ConnectionManager::sitlPort);
13    if (inet_pton(AF_INET, sitlIp.c_str(), &serv_addr.sin_addr) <= 0) {
14        XPLMDebugString("px4xplane: Invalid address or address not supported\n");
15        return;
16    }
17
18    if (connect(ConnectionManager::sockfd, (struct sockaddr*)&serv_addr, sizeof(serv_addr)) < 0) {
19        char errorMsg[128];
20        snprintf(errorMsg, sizeof(errorMsg), "px4xplane: Connection failed. Error: %s\n", strerror(errno));
21        XPLMDebugString(errorMsg);
22        return;
23    }
24
25    XPLMDebugString("px4xplane: Connected to SITL\n");
26
27    connected = true;
28    status = "Connected";
29    setLastMessage("Connected to SITL successfully.");
30}

When I try to connect to the SITL, I get the following message in the log: “px4xplane: Connection failed. Error: No error”. The SITL is running on a different machine (a WSL node) with the IP address 172.21.170.14.

I have also tried using the IP address 0.0.0.0, but the connection still fails. When I use 0.0.0.0, nothing happens, and when I use 172.21.170.14, X-Plane freezes for a few seconds and then resumes, but the connection is not established.

On my WSL, I run the command px4_sitl none_iris and I see the following output:

1INFO  [simulator_mavlink] using TCP on remote host 172.21.160.1 port 4560
2WARN  [simulator_mavlink] Please ensure port 4560 is not blocked by a firewall.
3INFO  [simulator_mavlink] Resolved host '172.21.160.1' to address: 172.21.160.1
4INFO  [simulator_mavlink] Waiting for simulator to accept connection on TCP port 4560

I have also set the environment variable PX4_SIM_HOSTNAME=172.21.160.1.

I have checked that the SITL is running and listening on the correct port, and there are no firewalls or network issues that could be blocking the connection.

I would appreciate any help or suggestions on how to resolve this issue. Thank you.

update
I changed how I establish the network and now on sitl I see:

INFO  [simulator_mavlink] Resolved host '172.21.160.1' to address: 172.21.160.1
INFO  [simulator_mavlink] Waiting for simulator to accept connection on TCP port 4560
INFO  [simulator_mavlink] Simulator connected on TCP port 4560.
ERROR [simulator_mavlink] poll timeout 0, 111
ERROR [simulator_mavlink] poll timeout 0, 111
ERROR [simulator_mavlink] poll timeout 0, 111
ERROR [simulator_mavlink] poll timeout 0, 111

and on logs I see"
px4xplane: Waiting for SITL connection…
px4xplane: Connected to SITL
px4xplane: Error sending data: No error
px4xplane: Error sending data: No error
px4xplane: Error sending data: No error
px4xplane: Error sending data: No error
px4xplane: Error sending data: No error

the code for connection;

void ConnectionManager::connectToSITL(const std::string& sitlIp) {
    if (connected) return;

    sockfd = socket(AF_INET, SOCK_STREAM, 0);
    if (sockfd < 0) {
        XPLMDebugString("px4xplane: Error opening socket\n");
        return;
    }

    sockaddr_in serv_addr{};
    serv_addr.sin_family = AF_INET;
    serv_addr.sin_port = htons(sitlPort);
    serv_addr.sin_addr.s_addr = inet_addr(sitlIp.c_str());

    if (bind(sockfd, (struct sockaddr*)&serv_addr, sizeof(serv_addr)) < 0) {
        XPLMDebugString("px4xplane: Error on binding the socket\n");
        closeSocket(sockfd);
        return;
    }

    if (listen(sockfd, 5) < 0) {
        XPLMDebugString("px4xplane: Error on listening\n");
        closeSocket(sockfd);
        return;
    }

    XPLMDebugString("px4xplane: Waiting for SITL connection...\n");

    sockaddr_in client_addr{};
    socklen_t client_len = sizeof(client_addr);
    int newsockfd = accept(sockfd, (struct sockaddr*)&client_addr, &client_len);
    if (newsockfd < 0) {
        XPLMDebugString("px4xplane: Acceptance failed\n");
        closeSocket(sockfd);
        return;
    }

    XPLMDebugString("px4xplane: Connected to SITL\n");
    //closeSocket(sockfd); // Consider if you want to close the listening socket now or keep it for more connections.

    connected = true;
    status = "Connected";
    setLastMessage("Connected to SITL successfully.");
}

and the code for send data:

void ConnectionManager::sendData(const uint8_t* buffer, int len) {
    if (!connected) return;

    int bytesSent = send(ConnectionManager::sockfd, reinterpret_cast<const char*>(buffer), len, 0);
    if (bytesSent < 0) {
        char buf[256];
        snprintf(buf, sizeof(buf), "px4xplane: Error sending data: %s\n", strerror(errno));
        XPLMDebugString(buf);
    }
}

I’m not entirely sure if I’ve correctly established a network connection. I’m uncertain whether the Software in the Loop (SITL) should serve as the server and X-Plane as the client, or vice versa. My plan is to send sensor data to SITL using TCP port 4560 and also receive motor commands on this same TCP port. Could you please confirm if I’m on the right track?

I kinda solved it and I decided to give answer here to anyone looking for similar scenario :slight_smile:

first of all in your sitl (on wsl)instance make sure you set the host IP to where your xplane simulator is running (for my case)
export PX4_SIM_HOSTNAME=172.21.160.1
then run sitl
make px4_sitl none_iris

on xplane side remember your xplane simulator is the server and px4 side (wsl) is client
so I changed my connections like this


#include "ConnectionManager.h"
#if IBM
#include <winsock2.h>
#include <ws2tcpip.h> // For inet_pton
#pragma comment(lib, "Ws2_32.lib")
#endif
#if LIN || APL
#include <unistd.h>
#include <sys/socket.h>
#include <netinet/in.h>
#include <arpa/inet.h>

#endif
#include "XPLMUtilities.h"
#include <cstring>
#include <string>
#include <errno.h> 

static bool connected = false;
int ConnectionManager::sockfd = -1;
int ConnectionManager::newsockfd = -1;

int ConnectionManager::sitlPort = 4560;
std::string ConnectionManager::status = "Disconnected";
std::string ConnectionManager::lastMessage = "";

#if IBM
bool ConnectionManager::initializeWinSock() {
    WSADATA wsaData;
    if (WSAStartup(MAKEWORD(2, 2), &wsaData) != 0) {
        XPLMDebugString("px4xplane: Could not initialize Winsock.\n");
        return false;
    }
    return true;
}
#endif


void ConnectionManager::setupServerSocket() {
    XPLMDebugString("px4xplane: Setting up server socket...\n");

    if (sockfd != -1 || connected) {
        XPLMDebugString("px4xplane: Server socket already set up or connected, aborting new setup attempt.\n");
        return;
    }

    sockfd = socket(AF_INET, SOCK_STREAM, 0);
    if (sockfd < 0) {
        XPLMDebugString("px4xplane: Error opening socket.\n");
        return;
    }

    sockaddr_in serv_addr{};
    serv_addr.sin_family = AF_INET;
    serv_addr.sin_addr.s_addr = INADDR_ANY;
    serv_addr.sin_port = htons(sitlPort);

    if (bind(sockfd, (struct sockaddr*)&serv_addr, sizeof(serv_addr)) < 0) {
        XPLMDebugString("px4xplane: Error on binding.\n");
        closeSocket(sockfd);
        return;
    }

    if (listen(sockfd, 5) < 0) {
        XPLMDebugString("px4xplane: Error on listen.\n");
        closeSocket(sockfd);
        return;
    }
    XPLMDebugString("px4xplane: Server socket set up, waiting for connection...\n");
    acceptConnection();

}


void ConnectionManager::acceptConnection() {

    if (connected) {
        XPLMDebugString("px4xplane: Already connected, aborting new accept attempt.\n");
        return;
    }

    XPLMDebugString("px4xplane: Waiting for SITL connection...\n");

    sockaddr_in cli_addr{};
    socklen_t clilen = sizeof(cli_addr);

     newsockfd = accept(sockfd, (struct sockaddr*)&cli_addr, &clilen);
    if (newsockfd < 0) {
        XPLMDebugString("px4xplane: Error on accept.\n");
        return;
    }

    XPLMDebugString("px4xplane: Connected to SITL successfully.\n");
    connected = true;
    status = "Connected";
    setLastMessage("Connected to SITL successfully.");

    // You might want to spawn a thread to handle communication over newsockfd or set it to non-blocking mode.
}



void ConnectionManager::disconnect() {
    if (!connected) return;
    closeSocket(sockfd);
    sockfd = -1;
    closeSocket(newsockfd); // Close the newsockfd
    newsockfd = -1;
    connected = false;
    status = "Disconnected";
    setLastMessage("Disconnected from SITL.");
    XPLMDebugString("px4xplane: Disconnected from SITL\n");
}

void ConnectionManager::closeSocket(int& sockfd) {
    if (sockfd != INVALID_SOCKET) {
#if IBM
        closesocket(sockfd);
#elif LIN || APL
        close(sockfd);
#endif
        sockfd = -1; // set to -1 to indicate that the socket is no longer valid
    }



}
void ConnectionManager::sendData(const uint8_t* buffer, int len) {
    if (!connected) return;
    int totalBytesSent = 0;
    while (totalBytesSent < len) {
        int bytesSent = send(newsockfd, reinterpret_cast<const char*>(buffer) + totalBytesSent, len - totalBytesSent, 0);

        if (bytesSent < 0) {
            char buf[256];
#if IBM
            snprintf(buf, sizeof(buf), "px4xplane: Error sending data: %d\n", WSAGetLastError());
#elif LIN || APL
            snprintf(buf, sizeof(buf), "px4xplane: Error sending data: %s\n", strerror(errno));
#endif
            XPLMDebugString(buf);
            // Optionally, handle error, e.g., clean up and/or reconnect
            return;
        }
        else if (bytesSent == 0) {
            // The peer has closed the connection.
            XPLMDebugString("px4xplane: Peer has closed the connection\n");

            // Clean up and/or try to reconnect.
            return;
        }

        totalBytesSent += bytesSent;
    }
}


void ConnectionManager::receiveData() {
    if (!connected) return;

    char buffer[256];
    memset(buffer, 0, sizeof(buffer));

    int bytesReceived = recv(newsockfd, buffer, sizeof(buffer) - 1, 0);
    if (bytesReceived < 0) {
        XPLMDebugString("px4xplane: Error receiving data\n");
    }
    else if (bytesReceived > 0) {
        buffer[bytesReceived] = '\0'; // Null-terminate the received data
        setLastMessage(buffer); // Store the received message
        XPLMDebugString(buffer); // Write the received message to the X-Plane log
    }
}

bool ConnectionManager::isConnected() {
    return connected;
}

const std::string& ConnectionManager::getStatus() {
    return status;
}

void ConnectionManager::setLastMessage(const std::string& message) {
    lastMessage = message;
}

const std::string& ConnectionManager::getLastMessage() {
    return lastMessage;
}
#if IBM
void ConnectionManager::cleanupWinSock() {
    WSACleanup();
}
#endif

hope this helps
remember initialize and clean-up should be run at start nd end of your code.

i am working in connecting px4 to xplane along with mavsdk… so how you set the socket to connect with px4 … i run the command “make px4_sitl none_iris” then how to connect it with xplane12… i am using python3. px4 asking for TCP and xplane has UPD in it… so how connection possible?