APM:Libraries
SIM_XPlane.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 /*
16  simulator connector for XPlane
17 */
18 
19 #include "SIM_XPlane.h"
20 
21 #include <errno.h>
22 #include <fcntl.h>
23 #include <stdio.h>
24 #include <stdarg.h>
25 #include <sys/stat.h>
26 #include <sys/types.h>
27 
28 #include <AP_HAL/AP_HAL.h>
29 #include <DataFlash/DataFlash.h>
30 
31 extern const AP_HAL::HAL& hal;
32 
33 namespace SITL {
34 
35 XPlane::XPlane(const char *home_str, const char *frame_str) :
36  Aircraft(home_str, frame_str)
37 {
38  use_time_sync = false;
39  const char *colon = strchr(frame_str, ':');
40  if (colon) {
41  xplane_ip = colon+1;
42  }
43 
44  heli_frame = (strstr(frame_str, "-heli") != nullptr);
45 
46  socket_in.bind("0.0.0.0", bind_port);
47  printf("Waiting for XPlane data on UDP port %u and sending to port %u\n",
48  (unsigned)bind_port, (unsigned)xplane_port);
49 
50  // XPlane sensor data is not good enough for EKF. Use fake EKF by default
51  AP_Param::set_default_by_name("AHRS_EKF_TYPE", 10);
52  AP_Param::set_default_by_name("INS_GYR_CAL", 0);
53 }
54 
55 /*
56  change what data is requested from XPlane. This saves the user from
57  having to setup the data screen correctly
58  */
59 void XPlane::select_data(uint64_t usel_mask, uint64_t sel_mask)
60 {
61  struct PACKED {
62  uint8_t marker[5] { 'D', 'S', 'E', 'L', '0' };
63  uint32_t data[8] {};
64  } dsel;
65  uint8_t count = 0;
66  for (uint8_t i=0; i<64 && count<8; i++) {
67  if ((((uint64_t)1)<<i) & sel_mask) {
68  dsel.data[count++] = i;
69  printf("i=%u\n", (unsigned)i);
70  }
71  }
72  if (count != 0) {
73  socket_out.send(&dsel, sizeof(dsel));
74  printf("Selecting %u data types 0x%llx\n", (unsigned)count, (unsigned long long)sel_mask);
75  }
76 
77  struct PACKED {
78  uint8_t marker[5] { 'U', 'S', 'E', 'L', '0' };
79  uint32_t data[8] {};
80  } usel;
81  count = 0;
82 
83  // only de-select an output once, so we don't fight the user
84  usel_mask &= ~unselected_mask;
85  unselected_mask |= usel_mask;
86 
87  for (uint8_t i=0; i<64 && count<8; i++) {
88  if ((((uint64_t)1)<<i) & usel_mask) {
89  usel.data[count++] = i;
90  }
91  }
92  if (count != 0) {
93  socket_out.send(&usel, sizeof(usel));
94  printf("De-selecting %u data types 0x%llx\n", (unsigned)count, (unsigned long long)usel_mask);
95  }
96 }
97 
98 /*
99  receive data from X-Plane via UDP
100 */
102 {
103  uint8_t pkt[10000];
104  uint8_t *p = &pkt[5];
105  const uint8_t pkt_len = 36;
106  uint64_t data_mask = 0;
107  const uint64_t one = 1U;
108  const uint64_t required_mask = (one<<Times | one<<LatLonAlt | one<<Speed | one<<PitchRollHeading |
109  one<<LocVelDistTraveled | one<<AngularVelocities | one<<Gload |
110  one << Joystick1 | one << ThrottleCommand | one << Trim |
111  one << PropPitch | one << EngineRPM | one << PropRPM | one << Generator |
112  one << Mixture);
113  Location loc {};
114  Vector3f pos;
115  uint32_t wait_time_ms = 1;
116  uint32_t now = AP_HAL::millis();
117 
118  // if we are about to get another frame from X-Plane then wait longer
119  if (xplane_frame_time > wait_time_ms &&
121  wait_time_ms = 10;
122  }
123  ssize_t len = socket_in.recv(pkt, sizeof(pkt), wait_time_ms);
124 
125  if (len < pkt_len+5 || memcmp(pkt, "DATA", 4) != 0) {
126  // not a data packet we understand
127  goto failed;
128  }
129  len -= 5;
130 
131  if (!connected) {
132  // we now know the IP X-Plane is using
133  uint16_t port;
134  socket_in.last_recv_address(xplane_ip, port);
135  socket_out.connect(xplane_ip, xplane_port);
136  connected = true;
137  printf("Connected to %s:%u\n", xplane_ip, (unsigned)xplane_port);
138  }
139 
140  while (len >= pkt_len) {
141  const float *data = (const float *)p;
142  uint8_t code = p[0];
143  // keep a mask of what codes we have received
144  if (code < 64) {
145  data_mask |= (((uint64_t)1) << code);
146  }
147  switch (code) {
148  case Times: {
149  uint64_t tus = data[3] * 1.0e6f;
150  if (tus + time_base_us <= time_now_us) {
151  uint64_t tdiff = time_now_us - (tus + time_base_us);
152  if (tdiff > 1e6f) {
153  printf("X-Plane time reset %lu\n", (unsigned long)tdiff);
154  }
155  time_base_us = time_now_us - tus;
156  }
157  uint64_t tnew = time_base_us + tus;
158  //uint64_t dt = tnew - time_now_us;
159  //printf("dt %u\n", (unsigned)dt);
160  time_now_us = tnew;
161  break;
162  }
163 
164  case LatLonAlt: {
165  loc.lat = data[1] * 1e7;
166  loc.lng = data[2] * 1e7;
167  loc.alt = data[3] * FEET_TO_METERS * 100.0f;
168  const float altitude_above_ground = data[4] * FEET_TO_METERS;
169  ground_level = loc.alt * 0.01f - altitude_above_ground;
170  break;
171  }
172 
173  case Speed:
176  break;
177 
178  case AoA:
179  // ignored
180  break;
181 
182  case Trim:
183  if (heli_frame) {
184  // use flaps for collective as no direct collective data input
185  rcin[2] = data[4];
186  }
187  break;
188 
189  case PitchRollHeading: {
190  float roll, pitch, yaw;
191  pitch = radians(data[1]);
192  roll = radians(data[2]);
193  yaw = radians(data[3]);
194  dcm.from_euler(roll, pitch, yaw);
195  break;
196  }
197 
198  case AtmosphereWeather:
199  // ignored
200  break;
201 
202  case LocVelDistTraveled:
203  pos.y = data[1];
204  pos.z = -data[2];
205  pos.x = -data[3];
206  velocity_ef.y = data[4];
207  velocity_ef.z = -data[5];
208  velocity_ef.x = -data[6];
209  break;
210 
211  case AngularVelocities:
212  gyro.y = data[1];
213  gyro.x = data[2];
214  gyro.z = data[3];
215  break;
216 
217  case Gload:
218  accel_body.z = -data[5] * GRAVITY_MSS;
219  accel_body.x = data[6] * GRAVITY_MSS;
220  accel_body.y = data[7] * GRAVITY_MSS;
221  break;
222 
223  case Joystick1:
224  rcin_chan_count = 4;
225  rcin[0] = (data[2] + 1)*0.5f;
226  rcin[1] = (data[1] + 1)*0.5f;
227  rcin[3] = (data[3] + 1)*0.5f;
228  break;
229 
230  case ThrottleCommand: {
231  if (!heli_frame) {
232  /* getting joystick throttle input is very weird. The
233  * problem is that XPlane sends the ThrottleCommand packet
234  * both for joystick throttle input and for throttle that
235  * we have provided over the link. So we need some way to
236  * detect when we get our own values back. The trick used
237  * is to add throttle_magic to the values we send, then
238  * detect this offset in the data coming back. Very ugly,
239  * but I can't find a better way of allowing joystick
240  * input from XPlane10
241  */
242  bool has_magic = ((uint32_t)(data[1] * throttle_magic_scale) % 1000U) == (uint32_t)(throttle_magic * throttle_magic_scale);
243  if (data[1] < 0 ||
244  data[1] == throttle_sent ||
245  has_magic) {
246  break;
247  }
248  rcin[2] = data[1];
249  }
250  break;
251  }
252 
253  case PropPitch: {
254  break;
255  }
256 
257  case EngineRPM:
258  rpm1 = data[1];
259  break;
260 
261  case PropRPM:
262  rpm2 = data[1];
263  break;
264 
265  case Joystick2:
266  break;
267 
268  case Generator:
269  /*
270  in order to get interlock switch on helis we map the
271  "generator1 on/off" function of XPlane 10 to channel 8.
272  */
273  rcin_chan_count = 8;
274  rcin[7] = data[1];
275  break;
276 
277  case Mixture:
278  // map channel 6 and 7 from Mixture3 and Mixture4 for extra channels
280  rcin[5] = data[3];
281  rcin[6] = data[4];
282  break;
283  }
284  len -= pkt_len;
285  p += pkt_len;
286  }
287 
288  if (data_mask != required_mask) {
289  // ask XPlane to change what data it sends
290  uint64_t usel = data_mask & ~required_mask;
291  uint64_t sel = required_mask & ~data_mask;
292  usel &= ~unselected_mask;
293  if (usel || sel) {
294  select_data(usel, sel);
295  goto failed;
296  }
297  }
298  position = pos + position_zero;
299  update_position();
300  time_advance();
301 
304 
305  // the position may slowly deviate due to float accuracy and longitude scaling
306  if (get_distance(loc, location) > 4 || abs(loc.alt - location.alt)*0.01f > 2.0f) {
307  printf("X-Plane home reset dist=%f alt=%.1f/%.1f\n",
308  get_distance(loc, location), loc.alt*0.01f, location.alt*0.01f);
309  // reset home location
310  position_zero(-pos.x, -pos.y, -pos.z);
311  home.lat = loc.lat;
312  home.lng = loc.lng;
313  home.alt = loc.alt;
314  position.x = 0;
315  position.y = 0;
316  position.z = 0;
317  update_position();
318  time_advance();
319  }
320 
322 
323  if (now > last_data_time_ms && now - last_data_time_ms < 100) {
325  }
327 
328  report.data_count++;
329  report.frame_count++;
330  return true;
331 
332 failed:
333  if (AP_HAL::millis() - last_data_time_ms > 200) {
334  // don't extrapolate beyond 0.2s
335  return false;
336  }
337 
338  // advance time by 1ms
339  frame_time_us = 1000;
340  float delta_time = frame_time_us * 1e-6f;
341 
343 
344  extrapolate_sensors(delta_time);
345 
346  update_position();
347  time_advance();
349  report.frame_count++;
350  return false;
351 }
352 
353 
354 /*
355  send data to X-Plane via UDP
356 */
357 void XPlane::send_data(const struct sitl_input &input)
358 {
359  float aileron = (input.servos[0]-1500)/500.0f;
360  float elevator = (input.servos[1]-1500)/500.0f;
361  float throttle = (input.servos[2]-1000)/1000.0;
362  float rudder = (input.servos[3]-1500)/500.0f;
363  struct PACKED {
364  uint8_t marker[5] { 'D', 'A', 'T', 'A', '0' };
365  uint32_t code;
366  float data[8];
367  } d {};
368 
369  if (input.servos[0] == 0) {
370  aileron = 0;
371  }
372  if (input.servos[1] == 0) {
373  elevator = 0;
374  }
375  if (input.servos[2] == 0) {
376  throttle = 0;
377  }
378  if (input.servos[3] == 0) {
379  rudder = 0;
380  }
381 
382  // we add the throttle_magic to the throttle value we send so we
383  // can detect when we get it back
384  throttle = ((uint32_t)(throttle * 1000)) * 1.0e-3f + throttle_magic;
385 
386  uint8_t flap_chan;
389  float flap = (input.servos[flap_chan]-1000)/1000.0;
390  if (flap != last_flap) {
391  send_dref("sim/flightmodel/controls/flaprqst", flap);
392  send_dref("sim/aircraft/overflow/acf_flap_arm", flap>0?1:0);
393  }
394  }
395 
396  d.code = FlightCon;
397  d.data[0] = elevator;
398  d.data[1] = aileron;
399  d.data[2] = rudder;
400  d.data[4] = rudder;
401  socket_out.send(&d, sizeof(d));
402 
403  if (!heli_frame) {
404  d.code = ThrottleCommand;
405  d.data[0] = throttle;
406  d.data[1] = throttle;
407  d.data[2] = throttle;
408  d.data[3] = throttle;
409  d.data[4] = 0;
410  socket_out.send(&d, sizeof(d));
411  } else {
412  // send chan3 as collective pitch, on scale from -10 to +10
413  float collective = 10*(input.servos[2]-1500)/500.0;
414 
415  // and send throttle from channel 8
416  throttle = (input.servos[7]-1000)/1000.0;
417 
418  // allow for extra throttle outputs for special aircraft
419  float throttle2 = (input.servos[5]-1000)/1000.0;
420  float throttle3 = (input.servos[6]-1000)/1000.0;
421 
422  d.code = PropPitch;
423  d.data[0] = collective;
424  d.data[1] = -rudder*15; // reverse sense of rudder, 15 degrees pitch range
425  d.data[2] = 0;
426  d.data[3] = 0;
427  d.data[4] = 0;
428  socket_out.send(&d, sizeof(d));
429 
430  d.code = ThrottleCommand;
431  d.data[0] = throttle;
432  d.data[1] = throttle;
433  d.data[2] = throttle2;
434  d.data[3] = throttle3;
435  d.data[4] = 0;
436  socket_out.send(&d, sizeof(d));
437  }
438 
439  throttle_sent = throttle;
440 }
441 
442 
443 /*
444  send DREF to X-Plane via UDP
445 */
446 void XPlane::send_dref(const char *name, float value)
447 {
448  struct PACKED {
449  uint8_t marker[5] { 'D', 'R', 'E', 'F', '0' };
450  float value;
451  char name[500];
452  } d {};
453  d.value = value;
454  strcpy(d.name, name);
455  socket_out.send(&d, sizeof(d));
456 }
457 
458 /*
459  update the XPlane simulation by one time step
460  */
461 void XPlane::update(const struct sitl_input &input)
462 {
463  if (receive_data()) {
464  send_data(input);
465  }
466 
467  uint32_t now = AP_HAL::millis();
468  if (report.last_report_ms == 0) {
469  report.last_report_ms = now;
470  }
471  if (now - report.last_report_ms > 5000) {
472  float dt = (now - report.last_report_ms) * 1.0e-3f;
473  printf("Data rate: %.1f FPS Frame rate: %.1f FPS\n",
474  report.data_count/dt, report.frame_count/dt);
475  report.last_report_ms = now;
476  report.data_count = 0;
477  report.frame_count = 0;
478  }
479 }
480 
481 } // namespace SITL
Vector3f accel_body
Definition: SIM_Aircraft.h:142
int printf(const char *fmt,...)
Definition: stdio.c:113
Vector3f position
Definition: SIM_Aircraft.h:140
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
void select_data(uint64_t usel_mask, uint64_t sel_mask)
Definition: SIM_XPlane.cpp:59
bool heli_frame
Definition: SIM_XPlane.h:70
float get_distance(const struct Location &loc1, const struct Location &loc2)
Definition: location.cpp:36
void from_euler(float roll, float pitch, float yaw)
Definition: matrix3.cpp:26
void send_dref(const char *name, float value)
Definition: SIM_XPlane.cpp:446
Location location
Definition: SIM_Aircraft.h:127
const char * name
Definition: BusTest.cpp:11
float throttle_sent
Definition: SIM_XPlane.h:59
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
static bool find_channel(SRV_Channel::Aux_servo_function_t function, uint8_t &chan)
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
Vector3f accel_earth
Definition: SIM_XPlane.h:58
float airspeed_pitot
Definition: SIM_Aircraft.h:144
bool receive_data(void)
Definition: SIM_XPlane.cpp:101
bool connected
Definition: SIM_XPlane.h:60
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
Definition: AP_Common.h:142
#define GRAVITY_MSS
Definition: definitions.h:47
#define f(i)
Vector3f velocity_ef
Definition: SIM_Aircraft.h:136
T y
Definition: vector3.h:67
uint32_t millis()
Definition: system.cpp:157
uint64_t time_now_us
Definition: SIM_Aircraft.h:160
T z
Definition: vector3.h:67
const char * xplane_ip
Definition: SIM_XPlane.h:48
SocketAPM socket_in
Definition: SIM_XPlane.h:52
uint8_t rcin_chan_count
Definition: SIM_Aircraft.h:149
void update(const struct sitl_input &input)
Definition: SIM_XPlane.cpp:461
void update_mag_field_bf(void)
uint64_t frame_time_us
Definition: SIM_Aircraft.h:167
void update_position(void)
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
flap automated
Definition: SRV_Channel.h:47
static constexpr float radians(float deg)
Definition: AP_Math.h:158
void extrapolate_sensors(float delta_time)
uint32_t xplane_frame_time
Definition: SIM_XPlane.h:61
SocketAPM socket_out
Definition: SIM_XPlane.h:53
uint64_t unselected_mask
Definition: SIM_XPlane.h:72
void send_data(const struct sitl_input &input)
Definition: SIM_XPlane.cpp:357
#define PACKED
Definition: AP_Common.h:28
const float throttle_magic_scale
Definition: SIM_XPlane.h:76
float value
const float KNOTS_TO_METERS_PER_SECOND
Definition: SIM_Aircraft.h:192
Vector3f position_zero
Definition: SIM_XPlane.h:57
struct SITL::XPlane::@211 report
const float FEET_TO_METERS
Definition: SIM_Aircraft.h:191
uint64_t time_base_us
Definition: SIM_XPlane.h:55
uint32_t last_data_time_ms
Definition: SIM_XPlane.h:56
uint16_t bind_port
Definition: SIM_XPlane.h:50
XPlane(const char *home_str, const char *frame_str)
Definition: SIM_XPlane.cpp:35
uint16_t xplane_port
Definition: SIM_XPlane.h:49
float last_flap
Definition: SIM_XPlane.h:67
T x
Definition: vector3.h:67
static bool set_default_by_name(const char *name, float value)
Definition: AP_Param.cpp:2111
const float throttle_magic
Definition: SIM_XPlane.h:75