APM:Libraries
SIM_FlightAxis.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 FlightAxis
17 */
18 
19 #include "SIM_FlightAxis.h"
20 
21 #include <arpa/inet.h>
22 #include <errno.h>
23 #include <fcntl.h>
24 #include <stdio.h>
25 #include <stdarg.h>
26 #include <sys/stat.h>
27 #include <sys/types.h>
28 
29 #include <AP_HAL/AP_HAL.h>
30 #include <DataFlash/DataFlash.h>
31 #include "pthread.h"
32 
33 extern const AP_HAL::HAL& hal;
34 
35 using namespace SITL;
36 
37 // the asprintf() calls are not worth checking for SITL
38 #pragma GCC diagnostic ignored "-Wunused-result"
39 
40 static const struct {
41  const char *name;
42  float value;
43 } sim_defaults[] = {
44  { "AHRS_EKF_TYPE", 10 },
45  { "INS_GYR_CAL", 0 },
46  { "SERVO1_MIN", 1000 },
47  { "SERVO1_MAX", 2000 },
48  { "SERVO2_MIN", 1000 },
49  { "SERVO2_MAX", 2000 },
50  { "SERVO3_MIN", 1000 },
51  { "SERVO3_MAX", 2000 },
52  { "SERVO4_MIN", 1000 },
53  { "SERVO4_MAX", 2000 },
54  { "SERVO5_MIN", 1000 },
55  { "SERVO5_MAX", 2000 },
56  { "SERVO6_MIN", 1000 },
57  { "SERVO6_MAX", 2000 },
58  { "SERVO6_MIN", 1000 },
59  { "SERVO6_MAX", 2000 },
60  { "INS_ACC2OFFS_X", 0.001 },
61  { "INS_ACC2OFFS_Y", 0.001 },
62  { "INS_ACC2OFFS_Z", 0.001 },
63  { "INS_ACC2SCAL_X", 1.001 },
64  { "INS_ACC2SCAL_Y", 1.001 },
65  { "INS_ACC2SCAL_Z", 1.001 },
66  { "INS_ACCOFFS_X", 0.001 },
67  { "INS_ACCOFFS_Y", 0.001 },
68  { "INS_ACCOFFS_Z", 0.001 },
69  { "INS_ACCSCAL_X", 1.001 },
70  { "INS_ACCSCAL_Y", 1.001 },
71  { "INS_ACCSCAL_Z", 1.001 },
72 };
73 
74 
75 FlightAxis::FlightAxis(const char *home_str, const char *frame_str) :
76  Aircraft(home_str, frame_str)
77 {
78  use_time_sync = false;
79  rate_hz = 250 / target_speedup;
80  heli_demix = strstr(frame_str, "helidemix") != nullptr;
81  rev4_servos = strstr(frame_str, "rev4") != nullptr;
82  const char *colon = strchr(frame_str, ':');
83  if (colon) {
84  controller_ip = colon+1;
85  }
86  for (uint8_t i=0; i<ARRAY_SIZE(sim_defaults); i++) {
88  }
89 
90  /* Create the thread that will be waiting for data from FlightAxis */
91  mutex = hal.util->new_semaphore();
92 
93  int ret = pthread_create(&thread, NULL, update_thread, this);
94  if (ret != 0) {
95  AP_HAL::panic("SIM_FlightAxis: failed to create thread");
96  }
97 }
98 
99 /*
100  update thread trampoline
101  */
103 {
104  FlightAxis *flightaxis = (FlightAxis *)arg;
105 
106 #if defined(__CYGWIN__) || defined(__CYGWIN64__)
107  //Cygwin doesn't support pthread_setname_np
108 #elif defined(__APPLE__) && defined(__MACH__)
109  pthread_setname_np("ardupilot-flightaxis");
110 #else
111  pthread_setname_np(pthread_self(), "ardupilot-flightaxis");
112 #endif
113 
114  flightaxis->update_loop();
115  return nullptr;
116 }
117 
118 /*
119  main update loop
120  */
122 {
123  while (true) {
124  struct sitl_input new_input;
126  new_input = last_input;
127  mutex->give();
128  exchange_data(new_input);
129  }
130 }
131 
132 /*
133  extremely primitive SOAP parser that assumes the format used by FlightAxis
134 */
135 void FlightAxis::parse_reply(const char *reply)
136 {
137  const char *reply0 = reply;
138  for (uint16_t i=0; i<num_keys; i++) {
139  const char *p = strstr(reply, keytable[i].key);
140  if (p == nullptr) {
141  p = strstr(reply0, keytable[i].key);
142  }
143  if (p == nullptr) {
144  printf("Failed to find key %s\n", keytable[i].key);
145  controller_started = false;
146  break;
147  }
148  p += strlen(keytable[i].key) + 1;
149  double v;
150  if (strncmp(p, "true", 4) == 0) {
151  v = 1;
152  } else if (strncmp(p, "false", 5) == 0) {
153  v = 0;
154  } else {
155  v = atof(p);
156  }
157  keytable[i].ref = v;
158  // this assumes key order and allows us to decode arrays
159  p = strchr(p, '>');
160  if (p != nullptr) {
161  reply = p;
162  }
163  }
164 }
165 
166 
167 /*
168  make a SOAP request, returning body of reply
169  */
170 char *FlightAxis::soap_request(const char *action, const char *fmt, ...)
171 {
172  va_list ap;
173  char *req1;
174 
175  va_start(ap, fmt);
176  vasprintf(&req1, fmt, ap);
177  va_end(ap);
178 
179  //printf("%s\n", req1);
180 
181  // open SOAP socket to FlightAxis
182  SocketAPM sock(false);
183  if (!sock.connect(controller_ip, controller_port)) {
184  free(req1);
185  return nullptr;
186  }
187  sock.set_blocking(false);
188 
189  char *req;
190  asprintf(&req, R"(POST / HTTP/1.1
191 soapaction: '%s'
192 content-length: %u
193 content-type: text/xml;charset='UTF-8'
194 Connection: Keep-Alive
195 
196 %s)",
197  action,
198  (unsigned)strlen(req1), req1);
199  sock.send(req, strlen(req));
200  free(req1);
201  free(req);
202  char reply[10000];
203  memset(reply, 0, sizeof(reply));
204  ssize_t ret = sock.recv(reply, sizeof(reply)-1, 1000);
205  if (ret <= 0) {
206  printf("No data\n");
207  return nullptr;
208  }
209  char *p = strstr(reply, "Content-Length: ");
210  if (p == nullptr) {
211  printf("No Content-Length\n");
212  return nullptr;
213  }
214 
215  // get the content length
216  uint32_t content_length = strtoul(p+16, nullptr, 10);
217  char *body = strstr(p, "\r\n\r\n");
218  if (body == nullptr) {
219  printf("No body\n");
220  return nullptr;
221  }
222  body += 4;
223 
224  // get the rest of the body
225  int32_t expected_length = content_length + (body - reply);
226  if (expected_length >= (int32_t)sizeof(reply)) {
227  printf("Reply too large %i\n", expected_length);
228  return nullptr;
229  }
230  while (ret < expected_length) {
231  ssize_t ret2 = sock.recv(&reply[ret], sizeof(reply)-(1+ret), 100);
232  if (ret2 <= 0) {
233  return nullptr;
234  }
235  // nul terminate
236  reply[ret+ret2] = 0;
237  ret += ret2;
238  }
239  return strdup(reply);
240 }
241 
242 
243 
244 void FlightAxis::exchange_data(const struct sitl_input &input)
245 {
246  if (!controller_started ||
249  printf("Starting controller at %s\n", controller_ip);
250  // call a restore first. This allows us to connect after the aircraft is changed in RealFlight
251  char *reply = soap_request("RestoreOriginalControllerDevice", R"(<?xml version='1.0' encoding='UTF-8'?>
252 <soap:Envelope xmlns:soap='http://schemas.xmlsoap.org/soap/envelope/' xmlns:xsd='http://www.w3.org/2001/XMLSchema' xmlns:xsi='http://www.w3.org/2001/XMLSchema-instance'>
253 <soap:Body>
254 <RestoreOriginalControllerDevice><a>1</a><b>2</b></RestoreOriginalControllerDevice>
255 </soap:Body>
256 </soap:Envelope>)");
257  free(reply);
258  reply = soap_request("InjectUAVControllerInterface", R"(<?xml version='1.0' encoding='UTF-8'?>
259 <soap:Envelope xmlns:soap='http://schemas.xmlsoap.org/soap/envelope/' xmlns:xsd='http://www.w3.org/2001/XMLSchema' xmlns:xsi='http://www.w3.org/2001/XMLSchema-instance'>
260 <soap:Body>
261 <InjectUAVControllerInterface><a>1</a><b>2</b></InjectUAVControllerInterface>
262 </soap:Body>
263 </soap:Envelope>)");
264  free(reply);
266  controller_started = true;
267  }
268 
269  float scaled_servos[8];
270  for (uint8_t i=0; i<8; i++) {
271  scaled_servos[i] = (input.servos[i] - 1000) / 1000.0f;
272  }
273 
274  if (rev4_servos) {
275  // swap first 4 and last 4 servos, for quadplane testing
276  float saved[4];
277  memcpy(saved, &scaled_servos[0], sizeof(saved));
278  memcpy(&scaled_servos[0], &scaled_servos[4], sizeof(saved));
279  memcpy(&scaled_servos[4], saved, sizeof(saved));
280  }
281 
282  if (heli_demix) {
283  // FlightAxis expects "roll/pitch/collective/yaw" input
284  float swash1 = scaled_servos[0];
285  float swash2 = scaled_servos[1];
286  float swash3 = scaled_servos[2];
287 
288  float roll_rate = swash1 - swash2;
289  float pitch_rate = -((swash1+swash2) / 2.0f - swash3);
290 
291  scaled_servos[0] = constrain_float(roll_rate + 0.5, 0, 1);
292  scaled_servos[1] = constrain_float(pitch_rate + 0.5, 0, 1);
293  }
294 
295 
296  char *reply = soap_request("ExchangeData", R"(<?xml version='1.0' encoding='UTF-8'?><soap:Envelope xmlns:soap='http://schemas.xmlsoap.org/soap/envelope/' xmlns:xsd='http://www.w3.org/2001/XMLSchema' xmlns:xsi='http://www.w3.org/2001/XMLSchema-instance'>
297 <soap:Body>
298 <ExchangeData>
299 <pControlInputs>
300 <m-selectedChannels>255</m-selectedChannels>
301 <m-channelValues-0to1>
302 <item>%.4f</item>
303 <item>%.4f</item>
304 <item>%.4f</item>
305 <item>%.4f</item>
306 <item>%.4f</item>
307 <item>%.4f</item>
308 <item>%.4f</item>
309 <item>%.4f</item>
310 </m-channelValues-0to1>
311 </pControlInputs>
312 </ExchangeData>
313 </soap:Body>
314 </soap:Envelope>)",
315  scaled_servos[0],
316  scaled_servos[1],
317  scaled_servos[2],
318  scaled_servos[3],
319  scaled_servos[4],
320  scaled_servos[5],
321  scaled_servos[6],
322  scaled_servos[7]);
323 
324  if (reply) {
326  double lastt_s = state.m_currentPhysicsTime_SEC;
327  parse_reply(reply);
328  double dt = state.m_currentPhysicsTime_SEC - lastt_s;
329  if (dt > 0 && dt < 0.1) {
330  if (average_frame_time_s < 1.0e-6) {
332  }
333  average_frame_time_s = average_frame_time_s * 0.98 + dt * 0.02;
334  }
336  mutex->give();
337  free(reply);
338  }
339 }
340 
341 
342 /*
343  update the FlightAxis simulation by one time step
344  */
345 void FlightAxis::update(const struct sitl_input &input)
346 {
348 
349  last_input = input;
350 
351  double dt_seconds = state.m_currentPhysicsTime_SEC - last_time_s;
352  if (dt_seconds < 0) {
353  // cope with restarting RealFlight while connected
354  initial_time_s = time_now_us * 1.0e-6f;
357  mutex->give();
358  return;
359  }
360  if (dt_seconds < 0.00001f) {
361  float delta_time = 0.001;
362  // don't go past the next expected frame
363  if (delta_time + extrapolated_s > average_frame_time_s) {
364  delta_time = average_frame_time_s - extrapolated_s;
365  }
366  if (delta_time <= 0) {
367  usleep(1000);
368  mutex->give();
369  return;
370  }
371  time_now_us += delta_time * 1.0e6;
372  extrapolate_sensors(delta_time);
373  update_position();
375  mutex->give();
376  usleep(delta_time*1.0e6);
377  extrapolated_s += delta_time;
378  report_FPS();
379  return;
380  }
381 
382  extrapolated_s = 0;
383 
384  if (initial_time_s <= 0) {
385  dt_seconds = 0.001f;
387  }
388 
389  /*
390  the queternion convention in realflight seems to have Z negative
391  */
396  quat.rotation_matrix(dcm);
397 
401 
407  -state.m_altitudeASL_MTR - home.alt*0.01);
408 
412 
413  // accel on the ground is nasty in realflight, and prevents helicopter disarm
415  Vector3f accel_ef = (velocity_ef - last_velocity_ef) / dt_seconds;
416  accel_ef.z -= GRAVITY_MSS;
417  accel_body = dcm.transposed() * accel_ef;
418  }
419 
420  // limit to 16G to match pixhawk
421  float a_limit = GRAVITY_MSS*16;
422  accel_body.x = constrain_float(accel_body.x, -a_limit, a_limit);
423  accel_body.y = constrain_float(accel_body.y, -a_limit, a_limit);
424  accel_body.z = constrain_float(accel_body.z, -a_limit, a_limit);
425 
426  // offset based on first position to account for offset in RF world
429  }
431 
434 
438  rpm2 = state.m_propRPM;
439 
440  /*
441  the interlink interface supports 8 input channels
442  */
443  rcin_chan_count = 8;
444  for (uint8_t i=0; i<rcin_chan_count; i++) {
445  rcin[i] = state.rcin[i];
446  }
447 
448  update_position();
449  time_advance();
450  uint64_t new_time_us = (state.m_currentPhysicsTime_SEC - initial_time_s)*1.0e6;
451  if (new_time_us < time_now_us) {
452  uint64_t dt_us = time_now_us - new_time_us;
453  if (dt_us > 500000) {
454  // time going backwards
455  time_now_us = new_time_us;
456  }
457  } else {
458  time_now_us = new_time_us;
459  }
460 
462 
464 
465  // update magnetic field
467  mutex->give();
468 
469  report_FPS();
470 }
471 
472 /*
473  report frame rates
474  */
476 {
477  if (frame_counter++ % 1000 == 0) {
478  if (last_frame_count_s != 0) {
480  last_socket_frame_counter = socket_frame_counter;
482  printf("%.2f/%.2f FPS avg=%.2f\n",
483  frames / dt, 1000 / dt, 1.0/average_frame_time_s);
484  } else {
485  printf("Initial position %f %f %f\n", position.x, position.y, position.z);
486  }
488  }
489 }
Vector3f accel_body
Definition: SIM_Aircraft.h:142
int printf(const char *fmt,...)
Definition: stdio.c:113
struct sitl_input last_input
Vector3f position
Definition: SIM_Aircraft.h:140
Vector3< float > Vector3f
Definition: vector3.h:246
int vasprintf(char **strp, const char *fmt, va_list ap)
Definition: stdio.c:76
void parse_reply(const char *reply)
AP_HAL::Semaphore * mutex
float battery_voltage
Definition: SIM_Aircraft.h:145
AP_HAL::Util * util
Definition: HAL.h:115
const char * name
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
virtual Semaphore * new_semaphore(void)
Definition: Util.h:108
uint64_t activation_frame_counter
static void * update_thread(void *arg)
float battery_current
Definition: SIM_Aircraft.h:146
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
Matrix3< T > transposed(void) const
Definition: matrix3.cpp:189
FlightAxis(const char *home_str, const char *frame_str)
float airspeed_pitot
Definition: SIM_Aircraft.h:144
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
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define f(i)
const char * fmt
Definition: Printf.cpp:14
Vector3f velocity_ef
Definition: SIM_Aircraft.h:136
T y
Definition: vector3.h:67
uint16_t controller_port
uint64_t time_now_us
Definition: SIM_Aircraft.h:160
T z
Definition: vector3.h:67
Vector3f position_offset
void rotation_matrix(Matrix3f &m) const
Definition: quaternion.cpp:24
virtual bool give()=0
float v
Definition: Printf.cpp:15
uint8_t rcin_chan_count
Definition: SIM_Aircraft.h:149
const char * controller_ip
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
uint64_t socket_frame_counter
#define NULL
Definition: hal_types.h:59
Vector3f last_velocity_ef
void free(void *ptr)
Definition: malloc.c:81
void update_mag_field_bf(void)
static const struct @202 sim_defaults[]
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
void update_position(void)
char * soap_request(const char *action, const char *fmt,...)
static constexpr float radians(float deg)
Definition: AP_Math.h:158
void extrapolate_sensors(float delta_time)
bool is_zero(void) const
Definition: vector3.h:159
float value
void update_loop(void)
int asprintf(char **strp, const char *fmt,...)
Definition: stdio.c:91
uint64_t frame_counter
float target_speedup
Definition: SIM_Aircraft.h:166
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
static const uint16_t num_keys
void exchange_data(const struct sitl_input &input)
double average_frame_time_s
uint64_t last_socket_frame_counter
void zero()
Definition: vector3.h:182
T x
Definition: vector3.h:67
void update(const struct sitl_input &input)
static bool set_default_by_name(const char *name, float value)
Definition: AP_Param.cpp:2111