SIM_SilentWings.cpp 10 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318
  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 ardupilot version of SilentWings
  15. */
  16. #include "SIM_SilentWings.h"
  17. #include <stdio.h>
  18. #include <errno.h>
  19. #include <AP_HAL/AP_HAL.h>
  20. extern const AP_HAL::HAL& hal;
  21. using namespace SITL;
  22. static const struct {
  23. const char *name;
  24. float value;
  25. bool save;
  26. } sim_defaults[] = {
  27. { "AHRS_EKF_TYPE", 10 },
  28. { "INS_GYR_CAL", 0 },
  29. { "EK2_ENABLE", 0 },
  30. { "ARSPD_ENABLE", 1 },
  31. { "ARSPD_USE", 1 },
  32. { "INS_ACC2OFFS_X", 0.001 },
  33. { "INS_ACC2OFFS_Y", 0.001 },
  34. { "INS_ACC2OFFS_Z", 0.001 },
  35. { "INS_ACC2SCAL_X", 1.001 },
  36. { "INS_ACC2SCAL_Y", 1.001 },
  37. { "INS_ACC2SCAL_Z", 1.001 },
  38. { "INS_ACCOFFS_X", 0.001 },
  39. { "INS_ACCOFFS_Y", 0.001 },
  40. { "INS_ACCOFFS_Z", 0.001 },
  41. { "INS_ACCSCAL_X", 1.001 },
  42. { "INS_ACCSCAL_Y", 1.001 },
  43. { "INS_ACCSCAL_Z", 1.001 },
  44. };
  45. SilentWings::SilentWings(const char *frame_str) :
  46. Aircraft(frame_str),
  47. last_data_time_ms(0),
  48. first_pkt_timestamp_ms(0),
  49. time_base_us(0),
  50. sock(true),
  51. home_initialized(false),
  52. inited_first_pkt_timestamp(false)
  53. {
  54. // Force ArduPlane to use sensor data from SilentWings as the actual state,
  55. // without using EKF, i.e., using "fake EKF (type 10)". Disable gyro calibration.
  56. // Set a few other parameters to specific values to keep the calibration checks happy.
  57. // TO DO: fix this. Setting parameters in this way doesn't appear to have any effect.
  58. for (uint8_t i = 0; i < ARRAY_SIZE(sim_defaults); i++) {
  59. AP_Param::set_default_by_name(sim_defaults[i].name, sim_defaults[i].value);
  60. if (sim_defaults[i].save) {
  61. enum ap_var_type ptype;
  62. AP_Param *p = AP_Param::find(sim_defaults[i].name, &ptype);
  63. if (!p->configured()) {
  64. p->save();
  65. }
  66. }
  67. }
  68. }
  69. /*
  70. Create and set in/out socket
  71. */
  72. void SilentWings::set_interface_ports(const char* address, const int port_in, const int port_out)
  73. {
  74. // Ignore the specified port_in.
  75. // try to bind to a specific port so that if we restart ArduPilot
  76. // Gazebo keeps sending us packets. Not strictly necessary but
  77. // useful for debugging
  78. if (!sock.bind("127.0.0.1", _port_in)) {
  79. fprintf(stderr, "SITL: socket in bind failed on sim in : %d - %s\n", _port_in, strerror(errno));
  80. fprintf(stderr, "Aborting launch...\n");
  81. exit(1);
  82. }
  83. printf("Bind %s:%d for SITL in\n", "127.0.0.1", _port_in);
  84. sock.reuseaddress();
  85. sock.set_blocking(false);
  86. _sw_address = address;
  87. // Ignore the specified port_out.
  88. printf("Setting Silent Wings interface to %s:%d \n", _sw_address, _sw_port);
  89. }
  90. /*
  91. decode and send servos
  92. */
  93. void SilentWings::send_servos(const struct sitl_input &input)
  94. {
  95. char *buf = nullptr;
  96. // Turn off direct joystick input to the simulator. All joystick commands
  97. // should go through Mission Planner and get properly fused with ArduPlane's
  98. // control inputs when in automatic flight modes.
  99. float joystick = 0.0f;
  100. float aileron = filtered_servo_angle(input, 0);
  101. float elevator = filtered_servo_angle(input, 1);
  102. float throttle = filtered_servo_range(input, 2);
  103. float rudder = filtered_servo_angle(input, 3);
  104. ssize_t buflen = asprintf(&buf,
  105. "JOY %f\n"
  106. "AIL %f\n"
  107. "ELE %f\n"
  108. "RUD %f\n"
  109. "THR %f\n",
  110. joystick, aileron, elevator, rudder, throttle) - 1;
  111. if (buflen < 0) {
  112. fprintf(stderr, "Fatal: Failed to allocate enough space for data\n"),
  113. exit(1);
  114. }
  115. ssize_t sent = sock.sendto(buf, buflen, _sw_address, _sw_port);
  116. free(buf);
  117. if (sent < 0) {
  118. fprintf(stderr, "Fatal: Failed to send on control socket\n"),
  119. exit(1);
  120. }
  121. if (sent < buflen) {
  122. fprintf(stderr, "Failed to send all bytes on control socket\n");
  123. }
  124. }
  125. /*
  126. Receive an update from the FDM
  127. This is a blocking function
  128. */
  129. bool SilentWings::recv_fdm(void)
  130. {
  131. fdm_packet tmp_pkt;
  132. memset(&pkt, 0, sizeof(pkt));
  133. ssize_t nread = sock.recv(&tmp_pkt, sizeof(pkt), 0);
  134. // nread == -1 (255) means no data has arrived
  135. if (nread != sizeof(pkt)) {
  136. return false;
  137. }
  138. memcpy(&pkt, &tmp_pkt, sizeof(pkt));
  139. // data received successfully
  140. return true;
  141. }
  142. void SilentWings::process_packet()
  143. {
  144. // pkt.timestamp is the time of day in SilentWings, measured in ms
  145. // since midnight.
  146. // TO DO: check what happens when a flight in SW crosses midnight
  147. if (inited_first_pkt_timestamp) {
  148. uint64_t tus = (pkt.timestamp - first_pkt_timestamp_ms) * 1.0e3f;
  149. time_now_us = time_base_us + tus;
  150. }
  151. else {
  152. first_pkt_timestamp_ms = pkt.timestamp;
  153. time_base_us = time_now_us;
  154. inited_first_pkt_timestamp = true;
  155. }
  156. dcm.from_euler(radians(pkt.roll), radians(pkt.pitch), radians(pkt.yaw));
  157. accel_body = Vector3f(pkt.ax * GRAVITY_MSS, pkt.ay * GRAVITY_MSS, pkt.az * GRAVITY_MSS); // This is g-load.
  158. gyro = Vector3f(radians(pkt.d_roll), radians(pkt.d_pitch), radians(pkt.d_yaw));
  159. // SilentWings provides velocity in body frame.
  160. velocity_ef = dcm * Vector3f(pkt.vx, pkt.vy, pkt.vz);
  161. // SilentWings also provides velocity in body frame w.r.t. the wind, from which we can infer the wind.
  162. wind_ef = dcm * (Vector3f(pkt.vx, pkt.vy, pkt.vz) - Vector3f(pkt.vx_wind, pkt.vy_wind, pkt.vz_wind));
  163. airspeed = pkt.v_eas;
  164. airspeed_pitot = pkt.v_eas;
  165. Location curr_location;
  166. curr_location.lat = pkt.position_latitude * 1.0e7;
  167. curr_location.lng = pkt.position_longitude * 1.0e7;
  168. curr_location.alt = pkt.altitude_msl * 100.0f;
  169. ground_level = curr_location.alt * 0.01f - pkt.altitude_ground;
  170. Vector3f posdelta = home.get_distance_NED(curr_location);
  171. position.x = posdelta.x;
  172. position.y = posdelta.y;
  173. position.z = posdelta.z;
  174. update_position();
  175. // In case Silent Wings' reported location and our location calculated using an offset from the home location diverge, we need
  176. // to reset the home location.
  177. if (curr_location.get_distance(location) > 4 || abs(curr_location.alt - location.alt)*0.01f > 2.0f || !home_initialized) {
  178. printf("SilentWings home reset dist=%f alt=%.1f/%.1f\n",
  179. curr_location.get_distance(location), curr_location.alt*0.01f, location.alt*0.01f);
  180. // reset home location
  181. home.lat = curr_location.lat;
  182. home.lng = curr_location.lng;
  183. // Resetting altitude reference point in flight can throw off a bunch
  184. // of important calculations, so let the home altitude always be 0m MSL
  185. home.alt = 0;
  186. position.x = 0;
  187. position.y = 0;
  188. position.z = -curr_location.alt;
  189. home_initialized = true;
  190. update_position();
  191. }
  192. // Auto-adjust to Silent Wings' frame rate
  193. // This affects the data rate (without this adjustment, the data rate is
  194. // low no matter what the output_udp_rate in SW's options.dat file is).
  195. double deltat = (AP_HAL::millis() - last_data_time_ms) / 1000.0f;
  196. if (deltat < 0.01 && deltat > 0) {
  197. adjust_frame_time(1.0/deltat);
  198. }
  199. last_data_time_ms = AP_HAL::millis();
  200. report.data_count++;
  201. report.frame_count++;
  202. if (0) {
  203. printf("Delta: %f Time: %" PRIu64 "\n", deltat, time_now_us);
  204. printf("Accel.x %f\n", accel_body.x);
  205. printf("Accel.y %f\n", accel_body.y);
  206. printf("Accel.z %f\n", accel_body.z);
  207. printf("Gyro.x %f\n", gyro.x);
  208. printf("Gyro.y %f\n", gyro.y);
  209. printf("Gyro.z %f\n", gyro.z);
  210. printf("Pos.x %f\n", position.x);
  211. printf("Pos.y %f\n", position.y);
  212. printf("Pos.z %f\n", position.z);
  213. printf("Roll %f\n", pkt.roll);
  214. printf("Pitch %f\n", pkt.pitch);
  215. printf("Yaw %f\n", pkt.yaw);
  216. }
  217. }
  218. /*
  219. Extrapolates sensor data if Silent Wings hasn't sent us a data packet in a while.
  220. */
  221. bool SilentWings::interim_update()
  222. {
  223. if (AP_HAL::millis() - last_data_time_ms > 200) {
  224. // don't extrapolate beyond 0.2s
  225. return false;
  226. }
  227. float delta_time = frame_time_us * 1e-6f;
  228. time_now_us += frame_time_us;
  229. extrapolate_sensors(delta_time);
  230. update_position();
  231. report.frame_count++;
  232. return true;
  233. }
  234. /*
  235. Update the Silent Wings simulation by one time step.
  236. */
  237. void SilentWings::update(const struct sitl_input &input)
  238. {
  239. if (recv_fdm()) {
  240. process_packet();
  241. // Time has been advanced by process_packet(.)
  242. send_servos(input);
  243. }
  244. else if (interim_update()) {
  245. // This clause is triggered only if we previously
  246. // received at least one data packet.
  247. // Time has been advanced by interim_update(.)
  248. send_servos(input);
  249. }
  250. // This clause is triggered if and only if we haven't received
  251. // any data packets yet (and therefore didn't attempt
  252. // extrapolating data via interim_update(.) either).
  253. if (!inited_first_pkt_timestamp){
  254. time_advance();
  255. }
  256. else {
  257. if (use_time_sync) {
  258. sync_frame_time();
  259. }
  260. }
  261. update_mag_field_bf();
  262. uint32_t now = AP_HAL::millis();
  263. if (report.last_report_ms == 0) {
  264. report.last_report_ms = now;
  265. printf("Resetting last report time to now\n");
  266. }
  267. if (now - report.last_report_ms > 5000) {
  268. float dt = (now - report.last_report_ms) * 1.0e-3f;
  269. printf("Data rate: %.1f FPS Frame rate: %.1f FPS\n",
  270. report.data_count/dt, report.frame_count/dt);
  271. report.last_report_ms = now;
  272. report.data_count = 0;
  273. report.frame_count = 0;
  274. }
  275. }