SIM_FlightAxis.cpp 16 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527
  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. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. /*
  14. simulator connector for FlightAxis
  15. */
  16. #include "SIM_FlightAxis.h"
  17. #include <arpa/inet.h>
  18. #include <errno.h>
  19. #include <fcntl.h>
  20. #include <stdio.h>
  21. #include <stdarg.h>
  22. #include <sys/stat.h>
  23. #include <sys/types.h>
  24. #include <AP_HAL/AP_HAL.h>
  25. #include <AP_Logger/AP_Logger.h>
  26. #include "pthread.h"
  27. extern const AP_HAL::HAL& hal;
  28. using namespace SITL;
  29. // the asprintf() calls are not worth checking for SITL
  30. #pragma GCC diagnostic ignored "-Wunused-result"
  31. static const struct {
  32. const char *name;
  33. float value;
  34. bool save;
  35. } sim_defaults[] = {
  36. { "AHRS_EKF_TYPE", 10 },
  37. { "INS_GYR_CAL", 0 },
  38. { "RC1_MIN", 1000, true },
  39. { "RC1_MAX", 2000, true },
  40. { "RC2_MIN", 1000, true },
  41. { "RC2_MAX", 2000, true },
  42. { "RC3_MIN", 1000, true },
  43. { "RC3_MAX", 2000, true },
  44. { "RC4_MIN", 1000, true },
  45. { "RC4_MAX", 2000, true },
  46. { "RC2_REVERSED", 1 }, // interlink has reversed rc2
  47. { "SERVO1_MIN", 1000 },
  48. { "SERVO1_MAX", 2000 },
  49. { "SERVO2_MIN", 1000 },
  50. { "SERVO2_MAX", 2000 },
  51. { "SERVO3_MIN", 1000 },
  52. { "SERVO3_MAX", 2000 },
  53. { "SERVO4_MIN", 1000 },
  54. { "SERVO4_MAX", 2000 },
  55. { "SERVO5_MIN", 1000 },
  56. { "SERVO5_MAX", 2000 },
  57. { "SERVO6_MIN", 1000 },
  58. { "SERVO6_MAX", 2000 },
  59. { "SERVO6_MIN", 1000 },
  60. { "SERVO6_MAX", 2000 },
  61. { "INS_ACC2OFFS_X", 0.001 },
  62. { "INS_ACC2OFFS_Y", 0.001 },
  63. { "INS_ACC2OFFS_Z", 0.001 },
  64. { "INS_ACC2SCAL_X", 1.001 },
  65. { "INS_ACC2SCAL_Y", 1.001 },
  66. { "INS_ACC2SCAL_Z", 1.001 },
  67. { "INS_ACCOFFS_X", 0.001 },
  68. { "INS_ACCOFFS_Y", 0.001 },
  69. { "INS_ACCOFFS_Z", 0.001 },
  70. { "INS_ACCSCAL_X", 1.001 },
  71. { "INS_ACCSCAL_Y", 1.001 },
  72. { "INS_ACCSCAL_Z", 1.001 },
  73. };
  74. FlightAxis::FlightAxis(const char *frame_str) :
  75. Aircraft(frame_str)
  76. {
  77. use_time_sync = false;
  78. rate_hz = 250 / target_speedup;
  79. heli_demix = strstr(frame_str, "helidemix") != nullptr;
  80. rev4_servos = strstr(frame_str, "rev4") != nullptr;
  81. const char *colon = strchr(frame_str, ':');
  82. if (colon) {
  83. controller_ip = colon+1;
  84. }
  85. for (uint8_t i=0; i<ARRAY_SIZE(sim_defaults); i++) {
  86. AP_Param::set_default_by_name(sim_defaults[i].name, sim_defaults[i].value);
  87. if (sim_defaults[i].save) {
  88. enum ap_var_type ptype;
  89. AP_Param *p = AP_Param::find(sim_defaults[i].name, &ptype);
  90. if (!p->configured()) {
  91. p->save();
  92. }
  93. }
  94. }
  95. int ret = pthread_create(&thread, NULL, update_thread, this);
  96. if (ret != 0) {
  97. AP_HAL::panic("SIM_FlightAxis: failed to create thread");
  98. }
  99. }
  100. /*
  101. update thread trampoline
  102. */
  103. void *FlightAxis::update_thread(void *arg)
  104. {
  105. FlightAxis *flightaxis = (FlightAxis *)arg;
  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. flightaxis->update_loop();
  114. return nullptr;
  115. }
  116. /*
  117. main update loop
  118. */
  119. void FlightAxis::update_loop(void)
  120. {
  121. while (true) {
  122. struct sitl_input new_input;
  123. {
  124. WITH_SEMAPHORE(mutex);
  125. new_input = last_input;
  126. }
  127. exchange_data(new_input);
  128. }
  129. }
  130. /*
  131. extremely primitive SOAP parser that assumes the format used by FlightAxis
  132. */
  133. void FlightAxis::parse_reply(const char *reply)
  134. {
  135. const char *reply0 = reply;
  136. for (uint16_t i=0; i<num_keys; i++) {
  137. const char *p = strstr(reply, keytable[i].key);
  138. if (p == nullptr) {
  139. p = strstr(reply0, keytable[i].key);
  140. }
  141. if (p == nullptr) {
  142. printf("Failed to find key %s\n", keytable[i].key);
  143. controller_started = false;
  144. break;
  145. }
  146. p += strlen(keytable[i].key) + 1;
  147. double v;
  148. if (strncmp(p, "true", 4) == 0) {
  149. v = 1;
  150. } else if (strncmp(p, "false", 5) == 0) {
  151. v = 0;
  152. } else {
  153. v = atof(p);
  154. }
  155. keytable[i].ref = v;
  156. // this assumes key order and allows us to decode arrays
  157. p = strchr(p, '>');
  158. if (p != nullptr) {
  159. reply = p;
  160. }
  161. }
  162. }
  163. /*
  164. make a SOAP request, returning body of reply
  165. */
  166. char *FlightAxis::soap_request(const char *action, const char *fmt, ...)
  167. {
  168. va_list ap;
  169. char *req1;
  170. va_start(ap, fmt);
  171. vasprintf(&req1, fmt, ap);
  172. va_end(ap);
  173. //printf("%s\n", req1);
  174. // open SOAP socket to FlightAxis
  175. SocketAPM sock(false);
  176. if (!sock.connect(controller_ip, controller_port)) {
  177. free(req1);
  178. return nullptr;
  179. }
  180. sock.set_blocking(false);
  181. char *req;
  182. asprintf(&req, R"(POST / HTTP/1.1
  183. soapaction: '%s'
  184. content-length: %u
  185. content-type: text/xml;charset='UTF-8'
  186. Connection: Keep-Alive
  187. %s)",
  188. action,
  189. (unsigned)strlen(req1), req1);
  190. sock.send(req, strlen(req));
  191. free(req1);
  192. free(req);
  193. char reply[10000];
  194. memset(reply, 0, sizeof(reply));
  195. ssize_t ret = sock.recv(reply, sizeof(reply)-1, 1000);
  196. if (ret <= 0) {
  197. printf("No data\n");
  198. return nullptr;
  199. }
  200. char *p = strstr(reply, "Content-Length: ");
  201. if (p == nullptr) {
  202. printf("No Content-Length\n");
  203. return nullptr;
  204. }
  205. // get the content length
  206. uint32_t content_length = strtoul(p+16, nullptr, 10);
  207. char *body = strstr(p, "\r\n\r\n");
  208. if (body == nullptr) {
  209. printf("No body\n");
  210. return nullptr;
  211. }
  212. body += 4;
  213. // get the rest of the body
  214. int32_t expected_length = content_length + (body - reply);
  215. if (expected_length >= (int32_t)sizeof(reply)) {
  216. printf("Reply too large %i\n", expected_length);
  217. return nullptr;
  218. }
  219. while (ret < expected_length) {
  220. ssize_t ret2 = sock.recv(&reply[ret], sizeof(reply)-(1+ret), 100);
  221. if (ret2 <= 0) {
  222. return nullptr;
  223. }
  224. // nul terminate
  225. reply[ret+ret2] = 0;
  226. ret += ret2;
  227. }
  228. return strdup(reply);
  229. }
  230. void FlightAxis::exchange_data(const struct sitl_input &input)
  231. {
  232. if (!controller_started ||
  233. is_zero(state.m_flightAxisControllerIsActive) ||
  234. !is_zero(state.m_resetButtonHasBeenPressed)) {
  235. printf("Starting controller at %s\n", controller_ip);
  236. // call a restore first. This allows us to connect after the aircraft is changed in RealFlight
  237. char *reply = soap_request("RestoreOriginalControllerDevice", R"(<?xml version='1.0' encoding='UTF-8'?>
  238. <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'>
  239. <soap:Body>
  240. <RestoreOriginalControllerDevice><a>1</a><b>2</b></RestoreOriginalControllerDevice>
  241. </soap:Body>
  242. </soap:Envelope>)");
  243. free(reply);
  244. reply = soap_request("InjectUAVControllerInterface", R"(<?xml version='1.0' encoding='UTF-8'?>
  245. <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'>
  246. <soap:Body>
  247. <InjectUAVControllerInterface><a>1</a><b>2</b></InjectUAVControllerInterface>
  248. </soap:Body>
  249. </soap:Envelope>)");
  250. free(reply);
  251. activation_frame_counter = frame_counter;
  252. controller_started = true;
  253. }
  254. // maximum number of servos to send is 12 with new FlightAxis
  255. float scaled_servos[12];
  256. for (uint8_t i=0; i<ARRAY_SIZE(scaled_servos); i++) {
  257. scaled_servos[i] = (input.servos[i] - 1000) / 1000.0f;
  258. }
  259. if (rev4_servos) {
  260. // swap first 4 and last 4 servos, for quadplane testing
  261. float saved[4];
  262. memcpy(saved, &scaled_servos[0], sizeof(saved));
  263. memcpy(&scaled_servos[0], &scaled_servos[4], sizeof(saved));
  264. memcpy(&scaled_servos[4], saved, sizeof(saved));
  265. }
  266. if (heli_demix) {
  267. // FlightAxis expects "roll/pitch/collective/yaw" input
  268. float swash1 = scaled_servos[0];
  269. float swash2 = scaled_servos[1];
  270. float swash3 = scaled_servos[2];
  271. float roll_rate = swash1 - swash2;
  272. float pitch_rate = -((swash1+swash2) / 2.0f - swash3);
  273. scaled_servos[0] = constrain_float(roll_rate + 0.5, 0, 1);
  274. scaled_servos[1] = constrain_float(pitch_rate + 0.5, 0, 1);
  275. }
  276. 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'>
  277. <soap:Body>
  278. <ExchangeData>
  279. <pControlInputs>
  280. <m-selectedChannels>4095</m-selectedChannels>
  281. <m-channelValues-0to1>
  282. <item>%.4f</item>
  283. <item>%.4f</item>
  284. <item>%.4f</item>
  285. <item>%.4f</item>
  286. <item>%.4f</item>
  287. <item>%.4f</item>
  288. <item>%.4f</item>
  289. <item>%.4f</item>
  290. <item>%.4f</item>
  291. <item>%.4f</item>
  292. <item>%.4f</item>
  293. <item>%.4f</item>
  294. </m-channelValues-0to1>
  295. </pControlInputs>
  296. </ExchangeData>
  297. </soap:Body>
  298. </soap:Envelope>)",
  299. scaled_servos[0],
  300. scaled_servos[1],
  301. scaled_servos[2],
  302. scaled_servos[3],
  303. scaled_servos[4],
  304. scaled_servos[5],
  305. scaled_servos[6],
  306. scaled_servos[7],
  307. scaled_servos[8],
  308. scaled_servos[9],
  309. scaled_servos[10],
  310. scaled_servos[11]);
  311. if (reply) {
  312. WITH_SEMAPHORE(mutex);
  313. double lastt_s = state.m_currentPhysicsTime_SEC;
  314. parse_reply(reply);
  315. double dt = state.m_currentPhysicsTime_SEC - lastt_s;
  316. if (dt > 0 && dt < 0.1) {
  317. if (average_frame_time_s < 1.0e-6) {
  318. average_frame_time_s = dt;
  319. }
  320. average_frame_time_s = average_frame_time_s * 0.98 + dt * 0.02;
  321. }
  322. socket_frame_counter++;
  323. free(reply);
  324. }
  325. }
  326. /*
  327. update the FlightAxis simulation by one time step
  328. */
  329. void FlightAxis::update(const struct sitl_input &input)
  330. {
  331. WITH_SEMAPHORE(mutex);
  332. last_input = input;
  333. double dt_seconds = state.m_currentPhysicsTime_SEC - last_time_s;
  334. if (dt_seconds < 0) {
  335. // cope with restarting RealFlight while connected
  336. initial_time_s = time_now_us * 1.0e-6f;
  337. last_time_s = state.m_currentPhysicsTime_SEC;
  338. position_offset.zero();
  339. return;
  340. }
  341. if (dt_seconds < 0.00001f) {
  342. float delta_time = 0.001;
  343. // don't go past the next expected frame
  344. if (delta_time + extrapolated_s > average_frame_time_s) {
  345. delta_time = average_frame_time_s - extrapolated_s;
  346. }
  347. if (delta_time <= 0) {
  348. usleep(1000);
  349. return;
  350. }
  351. time_now_us += delta_time * 1.0e6;
  352. extrapolate_sensors(delta_time);
  353. update_position();
  354. update_mag_field_bf();
  355. usleep(delta_time*1.0e6);
  356. extrapolated_s += delta_time;
  357. report_FPS();
  358. return;
  359. }
  360. extrapolated_s = 0;
  361. if (initial_time_s <= 0) {
  362. dt_seconds = 0.001f;
  363. initial_time_s = state.m_currentPhysicsTime_SEC - dt_seconds;
  364. }
  365. /*
  366. the queternion convention in realflight seems to have Z negative
  367. */
  368. Quaternion quat(state.m_orientationQuaternion_W,
  369. state.m_orientationQuaternion_Y,
  370. state.m_orientationQuaternion_X,
  371. -state.m_orientationQuaternion_Z);
  372. quat.rotation_matrix(dcm);
  373. gyro = Vector3f(radians(constrain_float(state.m_rollRate_DEGpSEC, -2000, 2000)),
  374. radians(constrain_float(state.m_pitchRate_DEGpSEC, -2000, 2000)),
  375. -radians(constrain_float(state.m_yawRate_DEGpSEC, -2000, 2000))) * target_speedup;
  376. velocity_ef = Vector3f(state.m_velocityWorldU_MPS,
  377. state.m_velocityWorldV_MPS,
  378. state.m_velocityWorldW_MPS);
  379. position = Vector3f(state.m_aircraftPositionY_MTR,
  380. state.m_aircraftPositionX_MTR,
  381. -state.m_altitudeASL_MTR - home.alt*0.01);
  382. accel_body(state.m_accelerationBodyAX_MPS2,
  383. state.m_accelerationBodyAY_MPS2,
  384. state.m_accelerationBodyAZ_MPS2);
  385. // accel on the ground is nasty in realflight, and prevents helicopter disarm
  386. if (!is_zero(state.m_isTouchingGround)) {
  387. Vector3f accel_ef = (velocity_ef - last_velocity_ef) / dt_seconds;
  388. accel_ef.z -= GRAVITY_MSS;
  389. accel_body = dcm.transposed() * accel_ef;
  390. }
  391. // limit to 16G to match pixhawk
  392. float a_limit = GRAVITY_MSS*16;
  393. accel_body.x = constrain_float(accel_body.x, -a_limit, a_limit);
  394. accel_body.y = constrain_float(accel_body.y, -a_limit, a_limit);
  395. accel_body.z = constrain_float(accel_body.z, -a_limit, a_limit);
  396. // offset based on first position to account for offset in RF world
  397. if (position_offset.is_zero() || !is_zero(state.m_resetButtonHasBeenPressed)) {
  398. position_offset = position;
  399. }
  400. position -= position_offset;
  401. airspeed = state.m_airspeed_MPS;
  402. /* for pitot airspeed we need the airspeed along the X axis. We
  403. can't get that from m_airspeed_MPS, so instead we canculate it
  404. from wind vector and ground speed
  405. */
  406. Vector3f m_wind_ef(-state.m_windY_MPS,-state.m_windX_MPS,-state.m_windZ_MPS);
  407. Vector3f airspeed_3d_ef = m_wind_ef + velocity_ef;
  408. Vector3f airspeed3d = dcm.mul_transpose(airspeed_3d_ef);
  409. airspeed_pitot = MAX(airspeed3d.x,0);
  410. #if 0
  411. printf("WIND: %.1f %.1f %.1f AS3D %.1f %.1f %.1f\n",
  412. state.m_windX_MPS,
  413. state.m_windY_MPS,
  414. state.m_windZ_MPS,
  415. airspeed3d.x,
  416. airspeed3d.y,
  417. airspeed3d.z);
  418. #endif
  419. battery_voltage = state.m_batteryVoltage_VOLTS;
  420. battery_current = state.m_batteryCurrentDraw_AMPS;
  421. rpm1 = state.m_heliMainRotorRPM;
  422. rpm2 = state.m_propRPM;
  423. /*
  424. the interlink interface supports 8 input channels
  425. */
  426. rcin_chan_count = 8;
  427. for (uint8_t i=0; i<rcin_chan_count; i++) {
  428. rcin[i] = state.rcin[i];
  429. }
  430. update_position();
  431. time_advance();
  432. uint64_t new_time_us = (state.m_currentPhysicsTime_SEC - initial_time_s)*1.0e6;
  433. if (new_time_us < time_now_us) {
  434. uint64_t dt_us = time_now_us - new_time_us;
  435. if (dt_us > 500000) {
  436. // time going backwards
  437. time_now_us = new_time_us;
  438. }
  439. } else {
  440. time_now_us = new_time_us;
  441. }
  442. last_time_s = state.m_currentPhysicsTime_SEC;
  443. last_velocity_ef = velocity_ef;
  444. // update magnetic field
  445. update_mag_field_bf();
  446. report_FPS();
  447. }
  448. /*
  449. report frame rates
  450. */
  451. void FlightAxis::report_FPS(void)
  452. {
  453. if (frame_counter++ % 1000 == 0) {
  454. if (!is_zero(last_frame_count_s)) {
  455. uint64_t frames = socket_frame_counter - last_socket_frame_counter;
  456. last_socket_frame_counter = socket_frame_counter;
  457. double dt = state.m_currentPhysicsTime_SEC - last_frame_count_s;
  458. printf("%.2f/%.2f FPS avg=%.2f\n",
  459. frames / dt, 1000 / dt, 1.0/average_frame_time_s);
  460. } else {
  461. printf("Initial position %f %f %f\n", position.x, position.y, position.z);
  462. }
  463. last_frame_count_s = state.m_currentPhysicsTime_SEC;
  464. }
  465. }