"Number of Simulated Accelerometer Out of Range" in PX4 SITL while Sending HIL_SENSOR Messages

I am interfacing X-Plane with PX4 SITL using MAVLink and running into persistent issues with HIL_SENSOR messages. Even though my messages seem correctly formed and are sent with appropriate timing, I am receiving a recurring error: ERROR [simulator_mavlink] Number of simulated accelerometer out of range. Max: 3.

I am attempting to send simulated sensor data from X-Plane to PX4 SITL, with specific focus on HIL_SENSOR messages. I have ensured that the connection is well-established and that messages are appropriately timed and structured. Despite these precautions, the aforementioned error keeps appearing, indicating a potential misinterpretation of the messages by PX4.

Code Snippets:

Here are relevant portions of my code where I structure and dispatch the HIL_SENSOR messages:

void MAVLinkManager::sendHILSensor() {
    if (!ConnectionManager::isConnected()) return;

    mavlink_message_t msg;
    mavlink_hil_sensor_t hil_sensor;

    hil_sensor.time_usec = static_cast<uint64_t>(DataRefManager::getFloat("sim/time/total_flight_time_sec") * 1e6);

    hil_sensor.xacc = DataRefManager::getFloat("sim/flightmodel/forces/g_axil") * DataRefManager::g_earth;
    hil_sensor.yacc = DataRefManager::getFloat("sim/flightmodel/forces/g_side") * DataRefManager::g_earth;
    hil_sensor.zacc = DataRefManager::getFloat("sim/flightmodel/forces/g_nrml") * DataRefManager::g_earth;

    hil_sensor.xgyro = DataRefManager::getFloat("sim/flightmodel/position/Prad");
    hil_sensor.ygyro = DataRefManager::getFloat("sim/flightmodel/position/Qrad");
    hil_sensor.zgyro = DataRefManager::getFloat("sim/flightmodel/position/Rrad");

    hil_sensor.abs_pressure = DataRefManager::getFloat("sim/weather/barometer_current_inhg") * 33.8639;
    hil_sensor.pressure_alt = DataRefManager::getDouble("sim/flightmodel2/position/pressure_altitude") * 0.3048;
    // Find suitable datarefs or provide default values
    hil_sensor.diff_pressure = 0;
    hil_sensor.xmag = 0;
    hil_sensor.ymag = 0;
    hil_sensor.zmag = 0;

    hil_sensor.temperature = DataRefManager::getFloat("sim/cockpit2/temperature/outside_air_temp_degc");

    // Now set the bits for the fields you are updating.
    // Refer to the provided enum values for the fields_updated flags.
    //https://mavlink.io/en/messages/common.html#HIL_SENSOR_UPDATED_FLAGS
    uint32_t fields_updated = 0; // Start with a bitmask of all zeros
    fields_updated |= (1 << 0); // HIL_SENSOR_UPDATED_XACC, the bit shift corresponds to setting the 0th bit to 1
    fields_updated |= (1 << 1); // HIL_SENSOR_UPDATED_YACC, the bit shift corresponds to setting the 1st bit to 1
    fields_updated |= (1 << 2); // HIL_SENSOR_UPDATED_ZACC, the bit shift corresponds to setting the 2nd bit to 1
    fields_updated |= (1 << 3); // HIL_SENSOR_UPDATED_XGYRO, the bit shift corresponds to setting the 3rd bit to 1
    fields_updated |= (1 << 4); // HIL_SENSOR_UPDATED_YGYRO, the bit shift corresponds to setting the 4th bit to 1
    fields_updated |= (1 << 5); // HIL_SENSOR_UPDATED_ZGYRO, the bit shift corresponds to setting the 5th bit to 1
    fields_updated |= (1 << 9); // HIL_SENSOR_UPDATED_ABS_PRESSURE, the bit shift corresponds to setting the 9th bit to 1
    fields_updated |= (1 << 11); // HIL_SENSOR_UPDATED_PRESSURE_ALT, the bit shift corresponds to setting the 11th bit to 1
    fields_updated |= (1 << 12); // HIL_SENSOR_UPDATED_TEMPERATURE, the bit shift corresponds to setting the 12th bit to 1

    hil_sensor.fields_updated = fields_updated;

    // Finally, assign the bitmask to the hil_sensor message object
    hil_sensor.fields_updated = fields_updated;

    mavlink_msg_hil_sensor_encode(1, 1, &msg, &hil_sensor);
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    int len = mavlink_msg_to_send_buffer(buffer, &msg);
    ConnectionManager::sendData(buffer, len);
}

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;
    }
}

And, here is how it’s called in the plugin loop:

float MyFlightLoopCallback(float inElapsedSinceLastCall, float inElapsedTimeSinceLastFlightLoop, int inCounter, void* inRefcon) {
    if (!ConnectionManager::isConnected()) return -1.0f;
    MAVLinkManager::sendHILSensor();
    return -1.0f;
}
  1. Could any part of the code be causing PX4 to wrongly perceive the number of accelerometers in the HIL_SENSOR message?
  2. Is there any additional information or specific flags in the fields_updated bitmask that need to be set or avoided to prevent such discrepancies?
  3. Are there any related known bugs, and if so, are there workarounds or fixes available?

the source code is alsoavaible at