SIM_Frame.cpp 12 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292
  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. multicopter frame simulator class
  15. */
  16. #include "SIM_Frame.h"
  17. #include <AP_Motors/AP_Motors.h>
  18. #include <stdio.h>
  19. using namespace SITL;
  20. static Motor quad_plus_motors[] =
  21. {
  22. Motor(AP_MOTORS_MOT_1, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2),
  23. Motor(AP_MOTORS_MOT_2, -90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4),
  24. Motor(AP_MOTORS_MOT_3, 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1),
  25. Motor(AP_MOTORS_MOT_4, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3),
  26. };
  27. static Motor quad_x_motors[] =
  28. {
  29. Motor(AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1),
  30. Motor(AP_MOTORS_MOT_2, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3),
  31. Motor(AP_MOTORS_MOT_3, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4),
  32. Motor(AP_MOTORS_MOT_4, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2),
  33. };
  34. // motor order to match betaflight conventions
  35. // See: https://fpvfrenzy.com/betaflight-motor-order/
  36. static Motor quad_bf_x_motors[] =
  37. {
  38. Motor(AP_MOTORS_MOT_1, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2),
  39. Motor(AP_MOTORS_MOT_2, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW,1),
  40. Motor(AP_MOTORS_MOT_3, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW,3),
  41. Motor(AP_MOTORS_MOT_4, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4),
  42. };
  43. // motor order to match DJI conventions
  44. // See: https://forum44.djicdn.com/data/attachment/forum/201711/26/172348bppvtt1ot1nrtp5j.jpg
  45. static Motor quad_dji_x_motors[] =
  46. {
  47. Motor(AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1),
  48. Motor(AP_MOTORS_MOT_2, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4),
  49. Motor(AP_MOTORS_MOT_3, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3),
  50. Motor(AP_MOTORS_MOT_4, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2),
  51. };
  52. // motor order so that test order matches motor order ("clockwise X")
  53. static Motor quad_cw_x_motors[] =
  54. {
  55. Motor(AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1),
  56. Motor(AP_MOTORS_MOT_2, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2),
  57. Motor(AP_MOTORS_MOT_3, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3),
  58. Motor(AP_MOTORS_MOT_4, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4),
  59. };
  60. static Motor tiltquad_h_vectored_motors[] =
  61. {
  62. Motor(AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1, -1, 0, 0, 7, 10, -90),
  63. Motor(AP_MOTORS_MOT_2, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3, -1, 0, 0, 8, 10, -90),
  64. Motor(AP_MOTORS_MOT_3, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4, -1, 0, 0, 8, 10, -90),
  65. Motor(AP_MOTORS_MOT_4, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2, -1, 0, 0, 7, 10, -90),
  66. };
  67. static Motor hexa_motors[] =
  68. {
  69. Motor(AP_MOTORS_MOT_1, 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1),
  70. Motor(AP_MOTORS_MOT_2, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4),
  71. Motor(AP_MOTORS_MOT_3,-120, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5),
  72. Motor(AP_MOTORS_MOT_4, 60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2),
  73. Motor(AP_MOTORS_MOT_5, -60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6),
  74. Motor(AP_MOTORS_MOT_6, 120, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3)
  75. };
  76. static Motor hexax_motors[] =
  77. {
  78. Motor(AP_MOTORS_MOT_1, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2),
  79. Motor(AP_MOTORS_MOT_2, -90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5),
  80. Motor(AP_MOTORS_MOT_3, -30, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6),
  81. Motor(AP_MOTORS_MOT_4, 150, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3),
  82. Motor(AP_MOTORS_MOT_5, 30, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1),
  83. Motor(AP_MOTORS_MOT_6,-150, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4)
  84. };
  85. static Motor octa_motors[] =
  86. {
  87. Motor(AP_MOTORS_MOT_1, 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1),
  88. Motor(AP_MOTORS_MOT_2, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5),
  89. Motor(AP_MOTORS_MOT_3, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2),
  90. Motor(AP_MOTORS_MOT_4, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4),
  91. Motor(AP_MOTORS_MOT_5, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8),
  92. Motor(AP_MOTORS_MOT_6, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6),
  93. Motor(AP_MOTORS_MOT_7, -90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7),
  94. Motor(AP_MOTORS_MOT_8, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3)
  95. };
  96. static Motor octa_quad_motors[] =
  97. {
  98. Motor(AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1),
  99. Motor(AP_MOTORS_MOT_2, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7),
  100. Motor(AP_MOTORS_MOT_3, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5),
  101. Motor(AP_MOTORS_MOT_4, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3),
  102. Motor(AP_MOTORS_MOT_5, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8),
  103. Motor(AP_MOTORS_MOT_6, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2),
  104. Motor(AP_MOTORS_MOT_7, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4),
  105. Motor(AP_MOTORS_MOT_8, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6)
  106. };
  107. static Motor dodeca_hexa_motors[] =
  108. {
  109. Motor(AP_MOTORS_MOT_1, 30, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1),
  110. Motor(AP_MOTORS_MOT_2, 30, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2),
  111. Motor(AP_MOTORS_MOT_3, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3),
  112. Motor(AP_MOTORS_MOT_4, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4),
  113. Motor(AP_MOTORS_MOT_5, 150, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5),
  114. Motor(AP_MOTORS_MOT_6, 150, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6),
  115. Motor(AP_MOTORS_MOT_7, -150, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7),
  116. Motor(AP_MOTORS_MOT_8, -150, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8),
  117. Motor(AP_MOTORS_MOT_9, -90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 9),
  118. Motor(AP_MOTORS_MOT_10, -90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 10),
  119. Motor(AP_MOTORS_MOT_11, -30, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 11),
  120. Motor(AP_MOTORS_MOT_12, -30, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 12)
  121. };
  122. static Motor tri_motors[] =
  123. {
  124. Motor(AP_MOTORS_MOT_1, 60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1),
  125. Motor(AP_MOTORS_MOT_2, -60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3),
  126. Motor(AP_MOTORS_MOT_4, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2, AP_MOTORS_MOT_7, 60, -60, -1, 0, 0),
  127. };
  128. static Motor tilttri_motors[] =
  129. {
  130. Motor(AP_MOTORS_MOT_1, 60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1, -1, 0, 0, AP_MOTORS_MOT_8, 0, -90),
  131. Motor(AP_MOTORS_MOT_2, -60, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3, -1, 0, 0, AP_MOTORS_MOT_8, 0, -90),
  132. Motor(AP_MOTORS_MOT_4, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2, AP_MOTORS_MOT_7, 60, -60, -1, 0, 0),
  133. };
  134. static Motor tilttri_vectored_motors[] =
  135. {
  136. Motor(AP_MOTORS_MOT_1, 60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1, -1, 0, 0, 7, 10, -90),
  137. Motor(AP_MOTORS_MOT_2, -60, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3, -1, 0, 0, 8, 10, -90),
  138. Motor(AP_MOTORS_MOT_4, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2)
  139. };
  140. static Motor y6_motors[] =
  141. {
  142. Motor(AP_MOTORS_MOT_1, 60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2),
  143. Motor(AP_MOTORS_MOT_2, -60, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5),
  144. Motor(AP_MOTORS_MOT_3, -60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6),
  145. Motor(AP_MOTORS_MOT_4, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4),
  146. Motor(AP_MOTORS_MOT_5, 60, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1),
  147. Motor(AP_MOTORS_MOT_6, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3)
  148. };
  149. /*
  150. FireflyY6 is a Y6 with front motors tiltable using servo on channel 9 (output 8)
  151. */
  152. static Motor firefly_motors[] =
  153. {
  154. Motor(AP_MOTORS_MOT_1, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3),
  155. Motor(AP_MOTORS_MOT_2, 60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1, -1, 0, 0, 6, 0, -90),
  156. Motor(AP_MOTORS_MOT_3, -60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5, -1, 0, 0, 6, 0, -90),
  157. Motor(AP_MOTORS_MOT_4, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4),
  158. Motor(AP_MOTORS_MOT_5, 60, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2, -1, 0, 0, 6, 0, -90),
  159. Motor(AP_MOTORS_MOT_6, -60, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6, -1, 0, 0, 6, 0, -90)
  160. };
  161. /*
  162. table of supported frame types. String order is important for
  163. partial name matching
  164. */
  165. static Frame supported_frames[] =
  166. {
  167. Frame("+", 4, quad_plus_motors),
  168. Frame("quad", 4, quad_plus_motors),
  169. Frame("copter", 4, quad_plus_motors),
  170. Frame("x", 4, quad_x_motors),
  171. Frame("bfx", 4, quad_bf_x_motors),
  172. Frame("djix", 4, quad_dji_x_motors),
  173. Frame("cwx", 4, quad_cw_x_motors),
  174. Frame("tilthvec", 4, tiltquad_h_vectored_motors),
  175. Frame("hexax", 6, hexax_motors),
  176. Frame("hexa", 6, hexa_motors),
  177. Frame("octa-quad", 8, octa_quad_motors),
  178. Frame("octa", 8, octa_motors),
  179. Frame("dodeca-hexa", 12, dodeca_hexa_motors),
  180. Frame("tri", 3, tri_motors),
  181. Frame("tilttrivec",3, tilttri_vectored_motors),
  182. Frame("tilttri", 3, tilttri_motors),
  183. Frame("y6", 6, y6_motors),
  184. Frame("firefly", 6, firefly_motors)
  185. };
  186. void Frame::init(float _mass, float hover_throttle, float _terminal_velocity, float _terminal_rotation_rate)
  187. {
  188. /*
  189. scaling from total motor power to Newtons. Allows the copter
  190. to hover against gravity when each motor is at hover_throttle
  191. */
  192. thrust_scale = (_mass * GRAVITY_MSS) / (num_motors * hover_throttle);
  193. terminal_velocity = _terminal_velocity;
  194. terminal_rotation_rate = _terminal_rotation_rate;
  195. }
  196. /*
  197. find a frame by name
  198. */
  199. Frame *Frame::find_frame(const char *name)
  200. {
  201. for (uint8_t i=0; i < ARRAY_SIZE(supported_frames); i++) {
  202. // do partial name matching to allow for frame variants
  203. if (strncasecmp(name, supported_frames[i].name, strlen(supported_frames[i].name)) == 0) {
  204. return &supported_frames[i];
  205. }
  206. }
  207. return nullptr;
  208. }
  209. // calculate rotational and linear accelerations
  210. void Frame::calculate_forces(const Aircraft &aircraft,
  211. const struct sitl_input &input,
  212. Vector3f &rot_accel,
  213. Vector3f &body_accel)
  214. {
  215. Vector3f thrust; // newtons
  216. for (uint8_t i=0; i<num_motors; i++) {
  217. Vector3f mraccel, mthrust;
  218. motors[i].calculate_forces(input, thrust_scale, motor_offset, mraccel, mthrust);
  219. rot_accel += mraccel;
  220. thrust += mthrust;
  221. }
  222. body_accel = thrust/aircraft.gross_mass();
  223. if (terminal_rotation_rate > 0) {
  224. // rotational air resistance
  225. const Vector3f &gyro = aircraft.get_gyro();
  226. rot_accel.x -= gyro.x * radians(400.0) / terminal_rotation_rate;
  227. rot_accel.y -= gyro.y * radians(400.0) / terminal_rotation_rate;
  228. rot_accel.z -= gyro.z * radians(400.0) / terminal_rotation_rate;
  229. }
  230. if (terminal_velocity > 0) {
  231. // air resistance
  232. Vector3f air_resistance = -aircraft.get_velocity_air_ef() * (GRAVITY_MSS/terminal_velocity);
  233. body_accel += aircraft.get_dcm().transposed() * air_resistance;
  234. }
  235. // add some noise
  236. const float gyro_noise = radians(0.1);
  237. const float accel_noise = 0.3;
  238. const float noise_scale = thrust.length() / (thrust_scale * num_motors);
  239. rot_accel += Vector3f(aircraft.rand_normal(0, 1),
  240. aircraft.rand_normal(0, 1),
  241. aircraft.rand_normal(0, 1)) * gyro_noise * noise_scale;
  242. body_accel += Vector3f(aircraft.rand_normal(0, 1),
  243. aircraft.rand_normal(0, 1),
  244. aircraft.rand_normal(0, 1)) * accel_noise * noise_scale;
  245. }
  246. // calculate current and voltage
  247. void Frame::current_and_voltage(const struct sitl_input &input, float &voltage, float &current)
  248. {
  249. voltage = 0;
  250. current = 0;
  251. for (uint8_t i=0; i<num_motors; i++) {
  252. float c, v;
  253. motors[i].current_and_voltage(input, v, c, motor_offset);
  254. current += c;
  255. voltage += v;
  256. }
  257. // use average for voltage, total for current
  258. voltage /= num_motors;
  259. }