SIM_Scrimmage.cpp 6.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210
  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 Scrimmage simulator
  15. */
  16. #include "SIM_Scrimmage.h"
  17. #include <stdio.h>
  18. #include <inttypes.h>
  19. #include <sys/stat.h>
  20. #include <sys/types.h>
  21. #include <AP_HAL/AP_HAL.h>
  22. extern const AP_HAL::HAL& hal;
  23. namespace SITL {
  24. Scrimmage::Scrimmage(const char *_frame_str) :
  25. Aircraft(_frame_str),
  26. prev_timestamp_us(0),
  27. recv_sock(true),
  28. send_sock(true),
  29. frame_str(_frame_str)
  30. {
  31. // Set defaults for scrimmage-copter
  32. if (strcmp(frame_str, "scrimmage-copter")== 0) {
  33. mission_name = "arducopter.xml";
  34. motion_model = "Multirotor";
  35. visual_model = "iris";
  36. }
  37. }
  38. void Scrimmage::set_config(const char *config)
  39. {
  40. // The configuration string is a comma-separated sequence of key:value
  41. // pairs
  42. // Iterate over comma-separated strings and store parameters
  43. char *end_str;
  44. char* copy_config = strdup(config);
  45. char *token = strtok_r(copy_config, ",", &end_str);
  46. while (token != NULL)
  47. {
  48. char *end_token;
  49. char *token2 = strtok_r(token, "=", &end_token);
  50. if (strcmp(token2, "mission")==0) {
  51. mission_name = strtok_r(NULL, "=", &end_token);
  52. } else if (strcmp(token2, "motion_model")==0) {
  53. motion_model = strtok_r(NULL, "=", &end_token);
  54. } else if (strcmp(token2, "visual_model")==0) {
  55. visual_model = strtok_r(NULL, "=", &end_token);
  56. } else if (strcmp(token2, "terrain")==0) {
  57. terrain = strtok_r(NULL, "=", &end_token);
  58. } else {
  59. printf("Invalid scrimmage param: %s", token2);
  60. }
  61. token = strtok_r(NULL, ",", &end_str);
  62. }
  63. free(copy_config);
  64. // start scrimmage after parsing simulation configuration
  65. start_scrimmage();
  66. }
  67. void Scrimmage::set_interface_ports(const char* address, const int port_in, const int port_out)
  68. {
  69. fdm_port_in = port_in;
  70. fdm_port_out = port_out;
  71. fdm_address = address;
  72. printf("ArduPilot sending to scrimmage on %s:%d\n",fdm_address, fdm_port_out);
  73. printf("ArduPilot listening to scrimmage on %s:%d\n",fdm_address, fdm_port_in);
  74. recv_sock.bind(fdm_address, fdm_port_in);
  75. recv_sock.reuseaddress();
  76. recv_sock.set_blocking(false);
  77. send_sock.reuseaddress();
  78. send_sock.set_blocking(false);
  79. }
  80. // Start Scrimmage child
  81. void Scrimmage::start_scrimmage(void)
  82. {
  83. pid_t child_pid = fork();
  84. if (child_pid == 0) {
  85. // In child
  86. // Construct the scrimmage command string with overrides for initial
  87. // position and heading.
  88. char* full_exec_str;
  89. int len;
  90. // Get required string length
  91. len = snprintf(NULL, 0, "xterm +hold -T SCRIMMAGE -e 'scrimmage %s -o \"latitude_origin=%f,"
  92. "longitude_origin=%f,altitude_origin=%f,heading=%f,motion_model=%s,visual_model=%s,terrain=%s,"
  93. "to_ardupilot_port=%d,from_ardupilot_port=%d,to_ardupilot_ip=%s\"'", mission_name, home.lat*1.0e-7f,home.lng*1.0e-7f,
  94. home.alt*1.0e-2f, home_yaw, motion_model, visual_model, terrain, fdm_port_in, fdm_port_out, fdm_address);
  95. full_exec_str = (char *)malloc(len+1);
  96. snprintf(full_exec_str, len+1, "xterm +hold -T SCRIMMAGE -e 'scrimmage %s -o \"latitude_origin=%f,"
  97. "longitude_origin=%f,altitude_origin=%f,heading=%f,motion_model=%s,visual_model=%s,terrain=%s,"
  98. "to_ardupilot_port=%d,from_ardupilot_port=%d,to_ardupilot_ip=%s\"'", mission_name, home.lat*1.0e-7f,home.lng*1.0e-7f,
  99. home.alt*1.0e-2f, home_yaw, motion_model, visual_model, terrain, fdm_port_in, fdm_port_out, fdm_address);
  100. printf("%s\n", full_exec_str);
  101. // system call worked
  102. int ret = system(full_exec_str);
  103. if (ret != 0) {
  104. ::fprintf(stderr, "scrimmage didn't open.\n");
  105. perror("scrimmage");
  106. }
  107. free(full_exec_str);
  108. }
  109. }
  110. void Scrimmage::send_servos(const struct sitl_input &input)
  111. {
  112. servo_packet pkt;
  113. for (int i = 0; i < MAX_NUM_SERVOS; i++) {
  114. pkt.servos[i] = input.servos[i];
  115. }
  116. send_sock.sendto(&pkt, sizeof(servo_packet), fdm_address, fdm_port_out);
  117. }
  118. /*
  119. receive an update from the FDM
  120. This is a blocking function
  121. */
  122. void Scrimmage::recv_fdm(const struct sitl_input &input)
  123. {
  124. fdm_packet pkt;
  125. // wait for packet from scrimmage
  126. while (recv_sock.recv(&pkt, sizeof(pkt), 100) != sizeof(pkt));
  127. // auto-adjust to simulation frame rate
  128. uint64_t dt_us = 0;
  129. if (pkt.timestamp_us > prev_timestamp_us)
  130. dt_us = pkt.timestamp_us - prev_timestamp_us;
  131. time_now_us += dt_us;
  132. float dt_inv = 1.0e6 / ((float)dt_us);
  133. if ( dt_inv > 100) {
  134. adjust_frame_time(dt_inv);
  135. }
  136. prev_timestamp_us = pkt.timestamp_us;
  137. // dcm_bl: dcm from body to local frame
  138. dcm.from_euler(pkt.roll, pkt.pitch, pkt.yaw);
  139. dcm.normalize();
  140. // subtract gravity to get specific force measuremnt of the IMU
  141. accel_body = Vector3f(pkt.xAccel, pkt.yAccel, pkt.zAccel) - dcm.transposed()*Vector3f(0.0f, 0.0f, GRAVITY_MSS);
  142. gyro = Vector3f(pkt.rollRate, pkt.pitchRate, pkt.yawRate);
  143. ang_accel = (gyro - gyro_prev) * std::min((float)1000000, dt_inv);
  144. gyro_prev = gyro;
  145. velocity_ef = Vector3f(pkt.speedN, pkt.speedE, pkt.speedD);
  146. location.lat = pkt.latitude * 1.0e7;
  147. location.lng = pkt.longitude * 1.0e7;
  148. location.alt = pkt.altitude * 1.0e2;
  149. position.z = (home.alt - location.alt) * 1.0e-2;
  150. // velocity relative to air mass, in earth frame TODO
  151. velocity_air_ef = velocity_ef;
  152. // velocity relative to airmass in body frame TODO
  153. velocity_air_bf = dcm.transposed() * velocity_air_ef;
  154. battery_voltage = 0;
  155. battery_current = 0;
  156. rpm1 = 0;
  157. rpm2 = 0;
  158. airspeed = pkt.airspeed;
  159. airspeed_pitot = pkt.airspeed;
  160. }
  161. /*
  162. update the Scrimmage simulation by one time step
  163. */
  164. void Scrimmage::update(const struct sitl_input &input)
  165. {
  166. send_servos(input);
  167. recv_fdm(input);
  168. update_mag_field_bf();
  169. }
  170. } // namespace SITL