ArduPlane SITL with X-Plane 11. Can you help?

Hi,

I have quite bit of experience writing plugins for X-Plane going back a number of years, but ArduPilot is new to me.

So, I am trying to get ArduPlane working with X-Plane 11 as SITL, and I’ve made some progress. X-Plane 11/ArduPlane are successfully sending data to Mission Planner, and as I fly around (under manual control in X-Plane), I can see the plane’s progress on Mission Planner’s moving map and artificial horizon. Exciting :slight_smile:

However, I cannot get the data flowing the other way, i.e. I can’t get ArduPlane to send data to X-Plane.

I’ve been looking at the codebase (having set up a working toolchain) and I’m trying to figure out where things are going wrong. All softwares are latest versions as of today, and everything’s running on the same Windows 10 machine, that is: X-Plane 11, ArduPlane running under WSL, and Mission Planner. Here is my process:

  • In WSL, I run ArduPlane using build/sitl/bin/arduplane --base-port 5760 -r 50 -M xplane --irlock-port 9005. Note that I do not try to set the --sim-port-in or --sim-port-out options, as they appear to be hardcoded as 49001 and 49000 respectively in ardupilot/libraries/SITL/SIM_XPlane.h.
  • I run X-Plane 11.
  • I run Mission Planner.

Here are some notes on how I have X-Plane 11 configured:

On the Data Output page in Settings:

  • UDP Rate: 50 packets/sec
  • General Data Output tab:
    – IP Address: 127.0.0.1 <-- I’m running X-Plane 11, Mission Planner and ArduPlane (SITL) on the same PC.
    – Port: 49001 (default 49000) <-- I have found that specifying port 49001 is ESSENTIAL for Mission Planner to be able to read in data from X-Plane.
    – Data to Output: <-- This should be configured by ArduPlane automatically, but I can’t get that to work. Thus, I check these boxes manually:
    1 - Times
    3 - Speeds
    4 - Mach, VVI, g-load
    8 - Joystick aileron/joystick/rudder
    13 - Trim, flap, stats, & speedbrakes
    16 - Angular velocities
    17 - Pitch, roll, & headings
    20 - Latitude, longitude, & altitude
    21 - Location, velocity, & distance traveled (sic)
    25 - Throttle (commanded)
    29 - Mixture setting
    37 - Engine RPM
    38 - Propeller RPM
    39 - Propeller pitch
    58 - Generator on/off
  • Dataref read/write tab: <-- Irrelevant because ArduPlane uses UDP to send data to X-Plane, rather than Datarefs. Btw, UDP access to X-Plane has a problematic history.

On the Network page in Settings:

  • UDP PORTS:
    – Port we receive on: 49000 (default 49010) <-- One would expect 49000 to work, given that it’s specified in ardupilot/libraries/SITL/SIM_XPlane.h.
    – Port we receive on (legacy): 49000 (default 49000) <-- ???
    – Port we send from (legacy): 49001 (default 49001) <-- ???

Once everything is up and running, I make a few waypoints and select ‘Write WPs’. Then, when I try to ‘Arm’, I am given a failure message, whereupon I choose ‘Force Arm’. The aircraft status is now ‘Armed’. Next, I select ‘Auto’, but nothing happens. X-Plane is not receiving any data, so steering commands from ArduPlane aren’t honoured. My question is why?

I’d appreciate any help :slight_smile:

Pogo

Hi,
I haven’t used XPlane with Ardupilot before, actually not used Ardupilot with Windows also, but maybe I could help figure out the problem.

First, have you tried launching XPlane first and then SITL? This order is important for some simulators.
Also, are you getting any connection messages such as Link 1 down in the console or maybe some errors such as Connect failed in Xterm, etc.
This can indicate where the problem is

Hope this helps :slight_smile:
Rajat

I just had a look at SIM_XPlane.cpp, it doesn’t have any error output message when there’s a failure to connect.

If the above doesn’t work, then you can try adding an error message, something like

if (!socket_out.connect(xplane_ip, xplane_port)) {
    printf("Error while connecting to socket at %s:%u - Error: %s\n",
				 xplane_ip, xplane_port, strerror(errno));
}
connected = true;
printf("Connected to %s:%u\n", xplane_ip, (unsigned)xplane_port);

Hi Rajat,

Appreciate your help.

I inserted your check code and compiled. Turns out the connection is (and was) being made:

pogo@DESKTOP-9UG23ZO:~$ gox
Creating model xplane at speed 1.0
Home: -35.363261 149.165230 alt=584.000000m hdg=353.000000
Waiting for XPlane data on UDP port 49002 and sending to port 49000
Starting sketch ‘ArduPlane’
Starting SITL input
Using Irlock at port : 9005
bind port 5760 for 0
Serial port 0 on TCP port 5760
Waiting for connection …
Connection on serial port 0
bind port 5762 for 2
Serial port 2 on TCP port 5762
bind port 5763 for 3
Serial port 3 on TCP port 5763
Connected to 127.0.0.1:49000
X-Plane home reset dist=16638807.000000 alt=4.2/586.6
Data rate: 6.8 FPS Frame rate: 6.8 FPS
Data rate: 49.5 FPS Frame rate: 246.2 FPS
Data rate: 50.1 FPS Frame rate: 249.2 FPS
Data rate: 50.2 FPS Frame rate: 243.6 FPS
Data rate: 50.2 FPS Frame rate: 249.9 FPS
Data rate: 50.3 FPS Frame rate: 236.5 FPS
Data rate: 49.9 FPS Frame rate: 243.1 FPS
Data rate: 50.1 FPS Frame rate: 238.5 FPS
Data rate: 50.2 FPS Frame rate: 247.9 FPS
Data rate: 50.3 FPS Frame rate: 239.6 FPS
Data rate: 50.4 FPS Frame rate: 227.8 FPS
Data rate: 50.5 FPS Frame rate: 242.9 FPS
Data rate: 50.3 FPS Frame rate: 254.5 FPS
Data rate: 50.3 FPS Frame rate: 241.4 FPS
Data rate: 50.3 FPS Frame rate: 241.4 FPS
Data rate: 50.4 FPS Frame rate: 236.0 FPS

Note that I’ve also altered ardupilot/libraries/SITL/SIM_XPlane.h such that --sim-port-in is 49002, just to see if this works, and yes, it does (once I reflect the change in X-Plane’s settings).

However, I still can’t get ArduPlane to start steering the aircraft…

Pogo

Hi,
Sorry for the late reply.
From the information you gave, all the connections look fine, at least there’s nothing wrong which jumps out.
After searching around a bit, I found a few things which might be useful

Looking at the following seems like XPlane 11 should work similarly like 10 with Ardupilot

X-Plane 11 and Ardupilot SITL

Ardupilot - Soaring test with “X-Plane 11” flight simulator

You could also try adding a debug message while it’s sending the data as well

Note that it’s sending the data at multiple places, you might need to add this at all of them

ssize_t send_ret = socket_out.send(&pkt, sizeof(d));
	if (send_ret != sizeof(d)) {
		if (send_ret <= 0) {
			printf("Unable to send servo output- Error: %s, Return value: %ld\n", strerror(errno), send_ret);
		} else {
			printf("Sent %ld bytes instead of %ld bytes\n", send_ret, sizeof(d));
		}
	}

@Pogo Were you able to figure out the problem?
Just saw some posts in the Plane Simulation category which might be helpful

You could try this out

Hi Rajat,

Thanks so much for all your help. Really appreciate it. I’m pleased to say I have it working now.

The source of my confusion was X-Plane 11’s new user interface:

Notice the field that I’ve filled in with nonsense: 12345. One must not use this field. Put anything in it, but do NOT put 49000 or 49001 in it (at least, if one is running ArduPilot, X-Plane and Mission Planner on the same machine).

In other words, one must use the legacy UDP fields only!

And I didn’t see your last reply where you linked to the guy who’d already solved it… agh!

Golly, a lot of wasted time, but it’s good now. I’ve started by writing an X-Plane 11 plugin that reads in the mission file generated by Mission Planner, and plots the waypoints/paths using OpenGL calls. This way, one gets an immediate 3D appreciation of how well ArduPlane is following the path. I plan to develop the plugin over the coming weeks.

My next task is to understand the binary terrain data file that ArduPlane creates for terrain following. And again, I want to plot this data, which I understand is essentially a grid, in 3D, in X-Plane.

EDIT: Would be nice if the plugin could access everything it needs over UDP. I’m not sure how easy this would be, however.

Pogo

Hi,
Glad to know that you were able to get it working. This info is something which should be added to the Wiki, I’ll probably make a PR in a day or two for this

The plugin of yours sounds very interesting and useful, best of luck with it!
About accessing the data over UDP, you can have a look at this page, might be useful -
http://ardupilot.org/dev/docs/using-sitl-for-ardupilot-testing.html#connecting-other-additional-ground-stations

I have got control of steering wheel with changes in SIM_XPlane.cpp:
I added to the end of function void XPlane::send_data(const struct sitl_input &input):

float max_angle = 20.0;
float steering = (input.servos[9]-1500)/500.0f * max_angle;
send_dref("sim/operation/override/override_wheel_steer", 1.0);
send_dref("sim/flightmodel2/gear/tire_steer_actual_deg[0]", steering);

Now you gear will rotate between -20 +20 deg; from pwm out of 10 ch (1000: -20 deg, 1500: 0 deg, 2000: +20 deg);

Tested it with default Cesna.