AP_MotorsMatrix.cpp 43 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849
  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. * AP_MotorsMatrix.cpp - ArduCopter motors library
  15. * Code by RandyMackay. DIYDrones.com
  16. *
  17. */
  18. #include <AP_HAL/AP_HAL.h>
  19. #include "AP_MotorsMatrix.h"
  20. extern const AP_HAL::HAL& hal;
  21. // init
  22. void AP_MotorsMatrix::init(motor_frame_class frame_class, motor_frame_type frame_type)
  23. {
  24. // record requested frame class and type
  25. _last_frame_class = frame_class;
  26. _last_frame_type = frame_type;
  27. // setup the motors
  28. setup_motors(frame_class, frame_type);
  29. // enable fast channels or instant pwm
  30. set_update_rate(_speed_hz);
  31. }
  32. // set update rate to motors - a value in hertz
  33. void AP_MotorsMatrix::set_update_rate(uint16_t speed_hz)
  34. {
  35. // record requested speed
  36. _speed_hz = speed_hz;
  37. uint16_t mask = 0;
  38. for (uint8_t i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) {
  39. if (motor_enabled[i]) {
  40. mask |= 1U << i;
  41. }
  42. }
  43. rc_set_freq(mask, _speed_hz);
  44. }
  45. // set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus)
  46. void AP_MotorsMatrix::set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type)
  47. {
  48. // exit immediately if armed or no change
  49. if (armed() || (frame_class == _last_frame_class && _last_frame_type == frame_type)) {
  50. return;
  51. }
  52. _last_frame_class = frame_class;
  53. _last_frame_type = frame_type;
  54. // setup the motors
  55. setup_motors(frame_class, frame_type);
  56. // enable fast channels or instant pwm
  57. set_update_rate(_speed_hz);
  58. }
  59. void AP_MotorsMatrix::output_to_motors()
  60. {
  61. int8_t i;
  62. switch (_spool_state) {
  63. case SpoolState::SHUT_DOWN: {
  64. // no output
  65. for (i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) {
  66. if (motor_enabled[i]) {
  67. _actuator[i] = 0.0f;
  68. }
  69. }
  70. break;
  71. }
  72. case SpoolState::GROUND_IDLE:
  73. // sends output to motors when armed but not flying
  74. for (i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) {
  75. if (motor_enabled[i]) {
  76. set_actuator_with_slew(_actuator[i], actuator_spin_up_to_ground_idle());
  77. }
  78. }
  79. break;
  80. case SpoolState::SPOOLING_UP:
  81. case SpoolState::THROTTLE_UNLIMITED:
  82. case SpoolState::SPOOLING_DOWN:
  83. // set motor output based on thrust requests
  84. for (i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) {
  85. if (motor_enabled[i]) {
  86. set_actuator_with_slew(_actuator[i], thrust_to_actuator(_thrust_rpyt_out[i]));
  87. }
  88. }
  89. break;
  90. }
  91. // convert output to PWM and send to each motor
  92. for (i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) {
  93. if (motor_enabled[i]) {
  94. rc_write(i, output_to_pwm(_actuator[i]));
  95. }
  96. }
  97. }
  98. // get_motor_mask - returns a bitmask of which outputs are being used for motors (1 means being used)
  99. // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
  100. uint16_t AP_MotorsMatrix::get_motor_mask()
  101. {
  102. uint16_t motor_mask = 0;
  103. for (uint8_t i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) {
  104. if (motor_enabled[i]) {
  105. motor_mask |= 1U << i;
  106. }
  107. }
  108. uint16_t mask = rc_map_mask(motor_mask);
  109. // add parent's mask
  110. mask |= AP_MotorsMulticopter::get_motor_mask();
  111. return mask;
  112. }
  113. // output_armed - sends commands to the motors
  114. // includes new scaling stability patch
  115. void AP_MotorsMatrix::output_armed_stabilizing()
  116. {
  117. uint8_t i; // general purpose counter
  118. float roll_thrust; // roll thrust input value, +/- 1.0
  119. float pitch_thrust; // pitch thrust input value, +/- 1.0
  120. float yaw_thrust; // yaw thrust input value, +/- 1.0
  121. float throttle_thrust; // throttle thrust input value, 0.0 - 1.0
  122. float throttle_avg_max; // throttle thrust average maximum value, 0.0 - 1.0
  123. float throttle_thrust_max; // throttle thrust maximum value, 0.0 - 1.0
  124. float throttle_thrust_best_rpy; // throttle providing maximum roll, pitch and yaw range without climbing
  125. float rpy_scale = 1.0f; // this is used to scale the roll, pitch and yaw to fit within the motor limits
  126. float yaw_allowed = 1.0f; // amount of yaw we can fit in
  127. float thr_adj; // the difference between the pilot's desired throttle and throttle_thrust_best_rpy
  128. // apply voltage and air pressure compensation
  129. const float compensation_gain = get_compensation_gain(); // compensation for battery voltage and altitude
  130. roll_thrust = (_roll_in + _roll_in_ff) * compensation_gain;
  131. pitch_thrust = (_pitch_in + _pitch_in_ff) * compensation_gain;
  132. yaw_thrust = (_yaw_in + _yaw_in_ff) * compensation_gain;
  133. throttle_thrust = get_throttle() * compensation_gain;
  134. throttle_avg_max = _throttle_avg_max * compensation_gain;
  135. throttle_thrust_max = _thrust_boost_ratio + (1.0f - _thrust_boost_ratio) * _throttle_thrust_max;
  136. // sanity check throttle is above zero and below current limited throttle
  137. if (throttle_thrust <= 0.0f) {
  138. throttle_thrust = 0.0f;
  139. limit.throttle_lower = true;
  140. }
  141. if (throttle_thrust >= throttle_thrust_max) {
  142. throttle_thrust = throttle_thrust_max;
  143. limit.throttle_upper = true;
  144. }
  145. // ensure that throttle_avg_max is between the input throttle and the maximum throttle
  146. throttle_avg_max = constrain_float(throttle_avg_max, throttle_thrust, throttle_thrust_max);
  147. // calculate throttle that gives most possible room for yaw which is the lower of:
  148. // 1. 0.5f - (rpy_low+rpy_high)/2.0 - this would give the maximum possible margin above the highest motor and below the lowest
  149. // 2. the higher of:
  150. // a) the pilot's throttle input
  151. // b) the point _throttle_rpy_mix between the pilot's input throttle and hover-throttle
  152. // Situation #2 ensure we never increase the throttle above hover throttle unless the pilot has commanded this.
  153. // Situation #2b allows us to raise the throttle above what the pilot commanded but not so far that it would actually cause the copter to rise.
  154. // We will choose #1 (the best throttle for yaw control) if that means reducing throttle to the motors (i.e. we favor reducing throttle *because* it provides better yaw control)
  155. // We will choose #2 (a mix of pilot and hover throttle) only when the throttle is quite low. We favor reducing throttle instead of better yaw control because the pilot has commanded it
  156. // Under the motor lost condition we remove the highest motor output from our calculations and let that motor go greater than 1.0
  157. // To ensure control and maximum righting performance Hex and Octo have some optimal settings that should be used
  158. // Y6 : MOT_YAW_HEADROOM = 350, ATC_RAT_RLL_IMAX = 1.0, ATC_RAT_PIT_IMAX = 1.0, ATC_RAT_YAW_IMAX = 0.5
  159. // Octo-Quad (x8) x : MOT_YAW_HEADROOM = 300, ATC_RAT_RLL_IMAX = 0.375, ATC_RAT_PIT_IMAX = 0.375, ATC_RAT_YAW_IMAX = 0.375
  160. // Octo-Quad (x8) + : MOT_YAW_HEADROOM = 300, ATC_RAT_RLL_IMAX = 0.75, ATC_RAT_PIT_IMAX = 0.75, ATC_RAT_YAW_IMAX = 0.375
  161. // Usable minimums below may result in attitude offsets when motors are lost. Hex aircraft are only marginal and must be handles with care
  162. // Hex : MOT_YAW_HEADROOM = 0, ATC_RAT_RLL_IMAX = 1.0, ATC_RAT_PIT_IMAX = 1.0, ATC_RAT_YAW_IMAX = 0.5
  163. // Octo-Quad (x8) x : MOT_YAW_HEADROOM = 300, ATC_RAT_RLL_IMAX = 0.25, ATC_RAT_PIT_IMAX = 0.25, ATC_RAT_YAW_IMAX = 0.25
  164. // Octo-Quad (x8) + : MOT_YAW_HEADROOM = 300, ATC_RAT_RLL_IMAX = 0.5, ATC_RAT_PIT_IMAX = 0.5, ATC_RAT_YAW_IMAX = 0.25
  165. // Quads cannot make use of motor loss handling because it doesn't have enough degrees of freedom.
  166. // calculate amount of yaw we can fit into the throttle range
  167. // this is always equal to or less than the requested yaw from the pilot or rate controller
  168. float rp_low = 1.0f; // lowest thrust value
  169. float rp_high = -1.0f; // highest thrust value
  170. for (i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) {
  171. if (motor_enabled[i]) {
  172. // calculate the thrust outputs for roll and pitch
  173. _thrust_rpyt_out[i] = roll_thrust * _roll_factor[i] + pitch_thrust * _pitch_factor[i];
  174. // record lowest roll + pitch command
  175. if (_thrust_rpyt_out[i] < rp_low) {
  176. rp_low = _thrust_rpyt_out[i];
  177. }
  178. // record highest roll + pitch command
  179. if (_thrust_rpyt_out[i] > rp_high && (!_thrust_boost || i != _motor_lost_index)) {
  180. rp_high = _thrust_rpyt_out[i];
  181. }
  182. }
  183. }
  184. // include the lost motor scaled by _thrust_boost_ratio
  185. if (_thrust_boost && motor_enabled[_motor_lost_index]) {
  186. // record highest roll + pitch command
  187. if (_thrust_rpyt_out[_motor_lost_index] > rp_high) {
  188. rp_high = _thrust_boost_ratio * rp_high + (1.0f - _thrust_boost_ratio) * _thrust_rpyt_out[_motor_lost_index];
  189. }
  190. }
  191. // check for roll and pitch saturation
  192. if (rp_high - rp_low > 1.0f || throttle_avg_max < -rp_low) {
  193. // Full range is being used by roll and pitch.
  194. limit.roll = true;
  195. limit.pitch = true;
  196. }
  197. // calculate the highest allowed average thrust that will provide maximum control range
  198. throttle_thrust_best_rpy = MIN(0.5f, throttle_avg_max);
  199. // calculate the maximum yaw control that can be used
  200. // todo: make _yaw_headroom 0 to 1
  201. yaw_allowed = (float)_yaw_headroom / 1000.0f;
  202. yaw_allowed = _thrust_boost_ratio * 0.5f + (1.0f - _thrust_boost_ratio) * yaw_allowed;
  203. yaw_allowed = MAX(MIN(throttle_thrust_best_rpy + rp_low, 1.0f - (throttle_thrust_best_rpy + rp_high)), yaw_allowed);
  204. if (fabsf(yaw_thrust) > yaw_allowed) {
  205. // not all commanded yaw can be used
  206. yaw_thrust = constrain_float(yaw_thrust, -yaw_allowed, yaw_allowed);
  207. limit.yaw = true;
  208. }
  209. // add yaw control to thrust outputs
  210. float rpy_low = 1.0f; // lowest thrust value
  211. float rpy_high = -1.0f; // highest thrust value
  212. for (i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) {
  213. if (motor_enabled[i]) {
  214. _thrust_rpyt_out[i] = _thrust_rpyt_out[i] + yaw_thrust * _yaw_factor[i];
  215. // record lowest roll + pitch + yaw command
  216. if (_thrust_rpyt_out[i] < rpy_low) {
  217. rpy_low = _thrust_rpyt_out[i];
  218. }
  219. // record highest roll + pitch + yaw command
  220. if (_thrust_rpyt_out[i] > rpy_high && (!_thrust_boost || i != _motor_lost_index)) {
  221. rpy_high = _thrust_rpyt_out[i];
  222. }
  223. }
  224. }
  225. // include the lost motor scaled by _thrust_boost_ratio
  226. if (_thrust_boost) {
  227. // record highest roll + pitch + yaw command
  228. if (_thrust_rpyt_out[_motor_lost_index] > rpy_high && motor_enabled[_motor_lost_index]) {
  229. rpy_high = _thrust_boost_ratio * rpy_high + (1.0f - _thrust_boost_ratio) * _thrust_rpyt_out[_motor_lost_index];
  230. }
  231. }
  232. // calculate any scaling needed to make the combined thrust outputs fit within the output range
  233. if (rpy_high - rpy_low > 1.0f) {
  234. rpy_scale = 1.0f / (rpy_high - rpy_low);
  235. }
  236. if (is_negative(rpy_low)) {
  237. rpy_scale = MIN(rpy_scale, -throttle_avg_max / rpy_low);
  238. }
  239. // calculate how close the motors can come to the desired throttle
  240. rpy_high *= rpy_scale;
  241. rpy_low *= rpy_scale;
  242. throttle_thrust_best_rpy = -rpy_low;
  243. thr_adj = throttle_thrust - throttle_thrust_best_rpy;
  244. if (rpy_scale < 1.0f) {
  245. // Full range is being used by roll, pitch, and yaw.
  246. limit.roll = true;
  247. limit.pitch = true;
  248. limit.yaw = true;
  249. if (thr_adj > 0.0f) {
  250. limit.throttle_upper = true;
  251. }
  252. thr_adj = 0.0f;
  253. } else {
  254. if (thr_adj < 0.0f) {
  255. // Throttle can't be reduced to desired value
  256. // todo: add lower limit flag and ensure it is handled correctly in altitude controller
  257. thr_adj = 0.0f;
  258. } else if (thr_adj > 1.0f - (throttle_thrust_best_rpy + rpy_high)) {
  259. // Throttle can't be increased to desired value
  260. thr_adj = 1.0f - (throttle_thrust_best_rpy + rpy_high);
  261. limit.throttle_upper = true;
  262. }
  263. }
  264. // add scaled roll, pitch, constrained yaw and throttle for each motor
  265. for (i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) {
  266. if (motor_enabled[i]) {
  267. _thrust_rpyt_out[i] = throttle_thrust_best_rpy + thr_adj + (rpy_scale * _thrust_rpyt_out[i]);
  268. }
  269. }
  270. // check for failed motor
  271. check_for_failed_motor(throttle_thrust_best_rpy + thr_adj);
  272. }
  273. // check for failed motor
  274. // should be run immediately after output_armed_stabilizing
  275. // first argument is the sum of:
  276. // a) throttle_thrust_best_rpy : throttle level (from 0 to 1) providing maximum roll, pitch and yaw range without climbing
  277. // b) thr_adj: the difference between the pilot's desired throttle and throttle_thrust_best_rpy
  278. // records filtered motor output values in _thrust_rpyt_out_filt array
  279. // sets thrust_balanced to true if motors are balanced, false if a motor failure is detected
  280. // sets _motor_lost_index to index of failed motor
  281. void AP_MotorsMatrix::check_for_failed_motor(float throttle_thrust_best_plus_adj)
  282. {
  283. // record filtered and scaled thrust output for motor loss monitoring purposes
  284. float alpha = 1.0f / (1.0f + _loop_rate * 0.5f);
  285. for (uint8_t i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) {
  286. if (motor_enabled[i]) {
  287. _thrust_rpyt_out_filt[i] += alpha * (_thrust_rpyt_out[i] - _thrust_rpyt_out_filt[i]);
  288. }
  289. }
  290. float rpyt_high = 0.0f;
  291. float rpyt_sum = 0.0f;
  292. uint8_t number_motors = 0.0f;
  293. for (uint8_t i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) {
  294. if (motor_enabled[i]) {
  295. number_motors += 1;
  296. rpyt_sum += _thrust_rpyt_out_filt[i];
  297. // record highest thrust command
  298. if (_thrust_rpyt_out_filt[i] > rpyt_high) {
  299. rpyt_high = _thrust_rpyt_out_filt[i];
  300. // hold motor lost index constant while thrust balance is true
  301. if (_thrust_balanced) {
  302. _motor_lost_index = i;
  303. }
  304. }
  305. }
  306. }
  307. float thrust_balance = 1.0f;
  308. if (rpyt_sum > 0.1f) {
  309. thrust_balance = rpyt_high * number_motors / rpyt_sum;
  310. }
  311. // ensure thrust balance does not activate for multirotors with less than 6 motors
  312. if (number_motors >= 6 && thrust_balance >= 1.5f && _thrust_balanced) {
  313. _thrust_balanced = false;
  314. }
  315. if (thrust_balance <= 1.25f && !_thrust_balanced) {
  316. _thrust_balanced = true;
  317. }
  318. // check to see if thrust boost is using more throttle than _throttle_thrust_max
  319. if (_throttle_thrust_max > throttle_thrust_best_plus_adj && rpyt_high < 0.9f && _thrust_balanced) {
  320. _thrust_boost = false;
  321. }
  322. }
  323. // output_test_seq - spin a motor at the pwm value specified
  324. // motor_seq is the motor's sequence number from 1 to the number of motors on the frame
  325. // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
  326. void AP_MotorsMatrix::output_test_seq(uint8_t motor_seq, int16_t pwm)
  327. {
  328. // exit immediately if not armed
  329. if (!armed()) {
  330. return;
  331. }
  332. // loop through all the possible orders spinning any motors that match that description
  333. for (uint8_t i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) {
  334. if (motor_enabled[i] && _test_order[i] == motor_seq) {
  335. // turn on this motor
  336. rc_write(i, pwm);
  337. }
  338. }
  339. }
  340. // output_test_num - spin a motor connected to the specified output channel
  341. // (should only be performed during testing)
  342. // If a motor output channel is remapped, the mapped channel is used.
  343. // Returns true if motor output is set, false otherwise
  344. // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
  345. bool AP_MotorsMatrix::output_test_num(uint8_t output_channel, int16_t pwm)
  346. {
  347. if (!armed()) {
  348. return false;
  349. }
  350. // Is channel in supported range?
  351. if (output_channel > AP_MOTORS_MAX_NUM_MOTORS - 1) {
  352. return false;
  353. }
  354. // Is motor enabled?
  355. if (!motor_enabled[output_channel]) {
  356. return false;
  357. }
  358. rc_write(output_channel, pwm); // output
  359. return true;
  360. }
  361. // add_motor
  362. void AP_MotorsMatrix::add_motor_raw(int8_t motor_num, float roll_fac, float pitch_fac, float yaw_fac, uint8_t testing_order)
  363. {
  364. // ensure valid motor number is provided
  365. if (motor_num >= 0 && motor_num < AP_MOTORS_MAX_NUM_MOTORS) {
  366. // increment number of motors if this motor is being newly motor_enabled
  367. if (!motor_enabled[motor_num]) {
  368. motor_enabled[motor_num] = true;
  369. }
  370. // set roll, pitch, thottle factors and opposite motor (for stability patch)
  371. _roll_factor[motor_num] = roll_fac;
  372. _pitch_factor[motor_num] = pitch_fac;
  373. _yaw_factor[motor_num] = yaw_fac;
  374. // set order that motor appears in test
  375. _test_order[motor_num] = testing_order;
  376. // call parent class method
  377. add_motor_num(motor_num);
  378. }
  379. }
  380. // add_motor using just position and prop direction - assumes that for each motor, roll and pitch factors are equal
  381. void AP_MotorsMatrix::add_motor(int8_t motor_num, float angle_degrees, float yaw_factor, uint8_t testing_order)
  382. {
  383. add_motor(motor_num, angle_degrees, angle_degrees, yaw_factor, testing_order);
  384. }
  385. // add_motor using position and prop direction. Roll and Pitch factors can differ (for asymmetrical frames)
  386. void AP_MotorsMatrix::add_motor(int8_t motor_num, float roll_factor_in_degrees, float pitch_factor_in_degrees, float yaw_factor, uint8_t testing_order)
  387. {
  388. add_motor_raw(
  389. motor_num,
  390. cosf(radians(roll_factor_in_degrees + 90)),
  391. cosf(radians(pitch_factor_in_degrees)),
  392. yaw_factor,
  393. testing_order);
  394. }
  395. // remove_motor - disabled motor and clears all roll, pitch, throttle factors for this motor
  396. void AP_MotorsMatrix::remove_motor(int8_t motor_num)
  397. {
  398. // ensure valid motor number is provided
  399. if (motor_num >= 0 && motor_num < AP_MOTORS_MAX_NUM_MOTORS) {
  400. // disable the motor, set all factors to zero
  401. motor_enabled[motor_num] = false;
  402. _roll_factor[motor_num] = 0;
  403. _pitch_factor[motor_num] = 0;
  404. _yaw_factor[motor_num] = 0;
  405. }
  406. }
  407. void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_type frame_type)
  408. {
  409. // remove existing motors
  410. for (int8_t i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) {
  411. remove_motor(i);
  412. }
  413. bool success = true;
  414. switch (frame_class) {
  415. case MOTOR_FRAME_QUAD:
  416. switch (frame_type) {
  417. case MOTOR_FRAME_TYPE_PLUS:
  418. add_motor(AP_MOTORS_MOT_1, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2);
  419. add_motor(AP_MOTORS_MOT_2, -90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4);
  420. add_motor(AP_MOTORS_MOT_3, 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1);
  421. add_motor(AP_MOTORS_MOT_4, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3);
  422. break;
  423. case MOTOR_FRAME_TYPE_X:
  424. add_motor(AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1);
  425. add_motor(AP_MOTORS_MOT_2, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3);
  426. add_motor(AP_MOTORS_MOT_3, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4);
  427. add_motor(AP_MOTORS_MOT_4, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2);
  428. break;
  429. case MOTOR_FRAME_TYPE_BF_X:
  430. // betaflight quad X order
  431. // see: https://fpvfrenzy.com/betaflight-motor-order/
  432. add_motor(AP_MOTORS_MOT_1, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2);
  433. add_motor(AP_MOTORS_MOT_2, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW,1);
  434. add_motor(AP_MOTORS_MOT_3, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW,3);
  435. add_motor(AP_MOTORS_MOT_4, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4);
  436. break;
  437. case MOTOR_FRAME_TYPE_DJI_X:
  438. // DJI quad X order
  439. // see https://forum44.djicdn.com/data/attachment/forum/201711/26/172348bppvtt1ot1nrtp5j.jpg
  440. add_motor(AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1);
  441. add_motor(AP_MOTORS_MOT_2, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4);
  442. add_motor(AP_MOTORS_MOT_3, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3);
  443. add_motor(AP_MOTORS_MOT_4, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2);
  444. break;
  445. case MOTOR_FRAME_TYPE_CW_X:
  446. // "clockwise X" motor order. Motors are ordered clockwise from front right
  447. // matching test order
  448. add_motor(AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1);
  449. add_motor(AP_MOTORS_MOT_2, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2);
  450. add_motor(AP_MOTORS_MOT_3, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3);
  451. add_motor(AP_MOTORS_MOT_4, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4);
  452. break;
  453. case MOTOR_FRAME_TYPE_V:
  454. add_motor(AP_MOTORS_MOT_1, 45, 0.7981f, 1);
  455. add_motor(AP_MOTORS_MOT_2, -135, 1.0000f, 3);
  456. add_motor(AP_MOTORS_MOT_3, -45, -0.7981f, 4);
  457. add_motor(AP_MOTORS_MOT_4, 135, -1.0000f, 2);
  458. break;
  459. case MOTOR_FRAME_TYPE_H:
  460. // H frame set-up - same as X but motors spin in opposite directiSons
  461. add_motor(AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1);
  462. add_motor(AP_MOTORS_MOT_2, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3);
  463. add_motor(AP_MOTORS_MOT_3, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4);
  464. add_motor(AP_MOTORS_MOT_4, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2);
  465. break;
  466. case MOTOR_FRAME_TYPE_VTAIL:
  467. /*
  468. Tested with: Lynxmotion Hunter Vtail 400
  469. - inverted rear outward blowing motors (at a 40 degree angle)
  470. - should also work with non-inverted rear outward blowing motors
  471. - no roll in rear motors
  472. - no yaw in front motors
  473. - should fly like some mix between a tricopter and X Quadcopter
  474. Roll control comes only from the front motors, Yaw control only from the rear motors.
  475. Roll & Pitch factor is measured by the angle away from the top of the forward axis to each arm.
  476. Note: if we want the front motors to help with yaw,
  477. motors 1's yaw factor should be changed to sin(radians(40)). Where "40" is the vtail angle
  478. motors 3's yaw factor should be changed to -sin(radians(40))
  479. */
  480. add_motor(AP_MOTORS_MOT_1, 60, 60, 0, 1);
  481. add_motor(AP_MOTORS_MOT_2, 0, -160, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3);
  482. add_motor(AP_MOTORS_MOT_3, -60, -60, 0, 4);
  483. add_motor(AP_MOTORS_MOT_4, 0, 160, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2);
  484. break;
  485. case MOTOR_FRAME_TYPE_ATAIL:
  486. /*
  487. The A-Shaped VTail is the exact same as a V-Shaped VTail, with one difference:
  488. - The Yaw factors are reversed, because the rear motors are facing different directions
  489. With V-Shaped VTails, the props make a V-Shape when spinning, but with
  490. A-Shaped VTails, the props make an A-Shape when spinning.
  491. - Rear thrust on a V-Shaped V-Tail Quad is outward
  492. - Rear thrust on an A-Shaped V-Tail Quad is inward
  493. Still functions the same as the V-Shaped VTail mixing below:
  494. - Yaw control is entirely in the rear motors
  495. - Roll is is entirely in the front motors
  496. */
  497. add_motor(AP_MOTORS_MOT_1, 60, 60, 0, 1);
  498. add_motor(AP_MOTORS_MOT_2, 0, -160, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3);
  499. add_motor(AP_MOTORS_MOT_3, -60, -60, 0, 4);
  500. add_motor(AP_MOTORS_MOT_4, 0, 160, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2);
  501. break;
  502. case MOTOR_FRAME_TYPE_PLUSREV:
  503. // plus with reversed motor directions
  504. add_motor(AP_MOTORS_MOT_1, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2);
  505. add_motor(AP_MOTORS_MOT_2, -90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4);
  506. add_motor(AP_MOTORS_MOT_3, 0, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1);
  507. add_motor(AP_MOTORS_MOT_4, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3);
  508. break;
  509. default:
  510. // quad frame class does not support this frame type
  511. success = false;
  512. break;
  513. }
  514. break; // quad
  515. case MOTOR_FRAME_HEXA:
  516. switch (frame_type) {
  517. case MOTOR_FRAME_TYPE_PLUS:
  518. add_motor(AP_MOTORS_MOT_1, 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1);
  519. add_motor(AP_MOTORS_MOT_2, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4);
  520. add_motor(AP_MOTORS_MOT_3,-120, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5);
  521. add_motor(AP_MOTORS_MOT_4, 60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2);
  522. add_motor(AP_MOTORS_MOT_5, -60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6);
  523. add_motor(AP_MOTORS_MOT_6, 120, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3);
  524. break;
  525. case MOTOR_FRAME_TYPE_X:
  526. add_motor(AP_MOTORS_MOT_1, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2);
  527. add_motor(AP_MOTORS_MOT_2, -90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5);
  528. add_motor(AP_MOTORS_MOT_3, -30, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6);
  529. add_motor(AP_MOTORS_MOT_4, 150, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3);
  530. add_motor(AP_MOTORS_MOT_5, 30, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1);
  531. add_motor(AP_MOTORS_MOT_6,-150, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4);
  532. break;
  533. case MOTOR_FRAME_TYPE_H:
  534. // H is same as X except middle motors are closer to center
  535. add_motor_raw(AP_MOTORS_MOT_1, -1.0f, 0.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2);
  536. add_motor_raw(AP_MOTORS_MOT_2, 1.0f, 0.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5);
  537. add_motor_raw(AP_MOTORS_MOT_3, 1.0f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6);
  538. add_motor_raw(AP_MOTORS_MOT_4, -1.0f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3);
  539. add_motor_raw(AP_MOTORS_MOT_5, -1.0f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1);
  540. add_motor_raw(AP_MOTORS_MOT_6, 1.0f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4);
  541. break;
  542. default:
  543. // hexa frame class does not support this frame type
  544. success = false;
  545. break;
  546. }
  547. break;
  548. case MOTOR_FRAME_OCTA:
  549. switch (frame_type) {
  550. case MOTOR_FRAME_TYPE_PLUS:
  551. add_motor(AP_MOTORS_MOT_1, 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1);
  552. add_motor(AP_MOTORS_MOT_2, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5);
  553. add_motor(AP_MOTORS_MOT_3, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2);
  554. add_motor(AP_MOTORS_MOT_4, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4);
  555. add_motor(AP_MOTORS_MOT_5, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8);
  556. add_motor(AP_MOTORS_MOT_6, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6);
  557. add_motor(AP_MOTORS_MOT_7, -90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7);
  558. add_motor(AP_MOTORS_MOT_8, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3);
  559. break;
  560. case MOTOR_FRAME_TYPE_X:
  561. add_motor(AP_MOTORS_MOT_1, 22.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1);
  562. add_motor(AP_MOTORS_MOT_2, -157.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5);
  563. add_motor(AP_MOTORS_MOT_3, 67.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2);
  564. add_motor(AP_MOTORS_MOT_4, 157.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4);
  565. add_motor(AP_MOTORS_MOT_5, -22.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8);
  566. add_motor(AP_MOTORS_MOT_6, -112.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6);
  567. add_motor(AP_MOTORS_MOT_7, -67.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7);
  568. add_motor(AP_MOTORS_MOT_8, 112.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3);
  569. break;
  570. case MOTOR_FRAME_TYPE_V:
  571. add_motor_raw(AP_MOTORS_MOT_1, 0.83f, 0.34f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7);
  572. add_motor_raw(AP_MOTORS_MOT_2, -0.67f, -0.32f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3);
  573. add_motor_raw(AP_MOTORS_MOT_3, 0.67f, -0.32f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6);
  574. add_motor_raw(AP_MOTORS_MOT_4, -0.50f, -1.00f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4);
  575. add_motor_raw(AP_MOTORS_MOT_5, 1.00f, 1.00f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8);
  576. add_motor_raw(AP_MOTORS_MOT_6, -0.83f, 0.34f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2);
  577. add_motor_raw(AP_MOTORS_MOT_7, -1.00f, 1.00f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1);
  578. add_motor_raw(AP_MOTORS_MOT_8, 0.50f, -1.00f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5);
  579. break;
  580. case MOTOR_FRAME_TYPE_H:
  581. add_motor_raw(AP_MOTORS_MOT_1, -1.0f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1);
  582. add_motor_raw(AP_MOTORS_MOT_2, 1.0f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5);
  583. add_motor_raw(AP_MOTORS_MOT_3, -1.0f, 0.333f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2);
  584. add_motor_raw(AP_MOTORS_MOT_4, -1.0f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4);
  585. add_motor_raw(AP_MOTORS_MOT_5, 1.0f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8);
  586. add_motor_raw(AP_MOTORS_MOT_6, 1.0f, -0.333f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6);
  587. add_motor_raw(AP_MOTORS_MOT_7, 1.0f, 0.333f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7);
  588. add_motor_raw(AP_MOTORS_MOT_8, -1.0f, -0.333f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3);
  589. break;
  590. case MOTOR_FRAME_TYPE_I:
  591. add_motor_raw(AP_MOTORS_MOT_1, 0.333f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1);
  592. add_motor_raw(AP_MOTORS_MOT_2, -0.333f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5);
  593. add_motor_raw(AP_MOTORS_MOT_3, 1.0f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2);
  594. add_motor_raw(AP_MOTORS_MOT_4, 0.333f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4);
  595. add_motor_raw(AP_MOTORS_MOT_5, -0.333f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8);
  596. add_motor_raw(AP_MOTORS_MOT_6, -1.0f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6);
  597. add_motor_raw(AP_MOTORS_MOT_7, -1.0f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7);
  598. add_motor_raw(AP_MOTORS_MOT_8, 1.0f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3);
  599. break;
  600. default:
  601. // octa frame class does not support this frame type
  602. success = false;
  603. break;
  604. } // octa frame type
  605. break;
  606. case MOTOR_FRAME_OCTAQUAD:
  607. switch (frame_type) {
  608. case MOTOR_FRAME_TYPE_PLUS:
  609. add_motor(AP_MOTORS_MOT_1, 0, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1);
  610. add_motor(AP_MOTORS_MOT_2, -90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7);
  611. add_motor(AP_MOTORS_MOT_3, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5);
  612. add_motor(AP_MOTORS_MOT_4, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3);
  613. add_motor(AP_MOTORS_MOT_5, -90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8);
  614. add_motor(AP_MOTORS_MOT_6, 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2);
  615. add_motor(AP_MOTORS_MOT_7, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4);
  616. add_motor(AP_MOTORS_MOT_8, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6);
  617. break;
  618. case MOTOR_FRAME_TYPE_X:
  619. add_motor(AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1);
  620. add_motor(AP_MOTORS_MOT_2, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7);
  621. add_motor(AP_MOTORS_MOT_3, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5);
  622. add_motor(AP_MOTORS_MOT_4, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3);
  623. add_motor(AP_MOTORS_MOT_5, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8);
  624. add_motor(AP_MOTORS_MOT_6, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2);
  625. add_motor(AP_MOTORS_MOT_7, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4);
  626. add_motor(AP_MOTORS_MOT_8, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6);
  627. break;
  628. case MOTOR_FRAME_TYPE_V:
  629. add_motor(AP_MOTORS_MOT_1, 45, 0.7981f, 1);
  630. add_motor(AP_MOTORS_MOT_2, -45, -0.7981f, 7);
  631. add_motor(AP_MOTORS_MOT_3, -135, 1.0000f, 5);
  632. add_motor(AP_MOTORS_MOT_4, 135, -1.0000f, 3);
  633. add_motor(AP_MOTORS_MOT_5, -45, 0.7981f, 8);
  634. add_motor(AP_MOTORS_MOT_6, 45, -0.7981f, 2);
  635. add_motor(AP_MOTORS_MOT_7, 135, 1.0000f, 4);
  636. add_motor(AP_MOTORS_MOT_8, -135, -1.0000f, 6);
  637. break;
  638. case MOTOR_FRAME_TYPE_H:
  639. // H frame set-up - same as X but motors spin in opposite directions
  640. add_motor(AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1);
  641. add_motor(AP_MOTORS_MOT_2, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 7);
  642. add_motor(AP_MOTORS_MOT_3, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5);
  643. add_motor(AP_MOTORS_MOT_4, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3);
  644. add_motor(AP_MOTORS_MOT_5, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 8);
  645. add_motor(AP_MOTORS_MOT_6, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2);
  646. add_motor(AP_MOTORS_MOT_7, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4);
  647. add_motor(AP_MOTORS_MOT_8, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6);
  648. break;
  649. default:
  650. // octaquad frame class does not support this frame type
  651. success = false;
  652. break;
  653. }
  654. break;
  655. case MOTOR_FRAME_DODECAHEXA: {
  656. switch (frame_type) {
  657. case MOTOR_FRAME_TYPE_PLUS:
  658. add_motor(AP_MOTORS_MOT_1, 0, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1); // forward-top
  659. add_motor(AP_MOTORS_MOT_2, 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2); // forward-bottom
  660. add_motor(AP_MOTORS_MOT_3, 60, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3); // forward-right-top
  661. add_motor(AP_MOTORS_MOT_4, 60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4); // forward-right-bottom
  662. add_motor(AP_MOTORS_MOT_5, 120, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5); // back-right-top
  663. add_motor(AP_MOTORS_MOT_6, 120, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6); // back-right-bottom
  664. add_motor(AP_MOTORS_MOT_7, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7); // back-top
  665. add_motor(AP_MOTORS_MOT_8, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8); // back-bottom
  666. add_motor(AP_MOTORS_MOT_9, -120, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 9); // back-left-top
  667. add_motor(AP_MOTORS_MOT_10, -120, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 10); // back-left-bottom
  668. add_motor(AP_MOTORS_MOT_11, -60, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 11); // forward-left-top
  669. add_motor(AP_MOTORS_MOT_12, -60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 12); // forward-left-bottom
  670. break;
  671. case MOTOR_FRAME_TYPE_X:
  672. add_motor(AP_MOTORS_MOT_1, 30, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1); // forward-right-top
  673. add_motor(AP_MOTORS_MOT_2, 30, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2); // forward-right-bottom
  674. add_motor(AP_MOTORS_MOT_3, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3); // right-top
  675. add_motor(AP_MOTORS_MOT_4, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4); // right-bottom
  676. add_motor(AP_MOTORS_MOT_5, 150, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5); // back-right-top
  677. add_motor(AP_MOTORS_MOT_6, 150, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6); // back-right-bottom
  678. add_motor(AP_MOTORS_MOT_7, -150, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7); // back-left-top
  679. add_motor(AP_MOTORS_MOT_8, -150, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8); // back-left-bottom
  680. add_motor(AP_MOTORS_MOT_9, -90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 9); // left-top
  681. add_motor(AP_MOTORS_MOT_10, -90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 10); // left-bottom
  682. add_motor(AP_MOTORS_MOT_11, -30, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 11); // forward-left-top
  683. add_motor(AP_MOTORS_MOT_12, -30, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 12); // forward-left-bottom
  684. break;
  685. default:
  686. // dodeca-hexa frame class does not support this frame type
  687. success = false;
  688. break;
  689. }}
  690. break;
  691. case MOTOR_FRAME_Y6:
  692. switch (frame_type) {
  693. case MOTOR_FRAME_TYPE_Y6B:
  694. // Y6 motor definition with all top motors spinning clockwise, all bottom motors counter clockwise
  695. add_motor_raw(AP_MOTORS_MOT_1, -1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1);
  696. add_motor_raw(AP_MOTORS_MOT_2, -1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2);
  697. add_motor_raw(AP_MOTORS_MOT_3, 0.0f, -1.000f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3);
  698. add_motor_raw(AP_MOTORS_MOT_4, 0.0f, -1.000f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4);
  699. add_motor_raw(AP_MOTORS_MOT_5, 1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5);
  700. add_motor_raw(AP_MOTORS_MOT_6, 1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6);
  701. break;
  702. case MOTOR_FRAME_TYPE_Y6F:
  703. // Y6 motor layout for FireFlyY6
  704. add_motor_raw(AP_MOTORS_MOT_1, 0.0f, -1.000f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3);
  705. add_motor_raw(AP_MOTORS_MOT_2, -1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1);
  706. add_motor_raw(AP_MOTORS_MOT_3, 1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5);
  707. add_motor_raw(AP_MOTORS_MOT_4, 0.0f, -1.000f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4);
  708. add_motor_raw(AP_MOTORS_MOT_5, -1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2);
  709. add_motor_raw(AP_MOTORS_MOT_6, 1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6);
  710. break;
  711. default:
  712. add_motor_raw(AP_MOTORS_MOT_1, -1.0f, 0.666f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2);
  713. add_motor_raw(AP_MOTORS_MOT_2, 1.0f, 0.666f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5);
  714. add_motor_raw(AP_MOTORS_MOT_3, 1.0f, 0.666f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6);
  715. add_motor_raw(AP_MOTORS_MOT_4, 0.0f, -1.333f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4);
  716. add_motor_raw(AP_MOTORS_MOT_5, -1.0f, 0.666f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1);
  717. add_motor_raw(AP_MOTORS_MOT_6, 0.0f, -1.333f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3);
  718. break;
  719. }
  720. break;
  721. default:
  722. // matrix doesn't support the configured class
  723. success = false;
  724. break;
  725. } // switch frame_class
  726. // normalise factors to magnitude 0.5
  727. normalise_rpy_factors();
  728. _flags.initialised_ok = success;
  729. }
  730. // normalizes the roll, pitch and yaw factors so maximum magnitude is 0.5
  731. void AP_MotorsMatrix::normalise_rpy_factors()
  732. {
  733. float roll_fac = 0.0f;
  734. float pitch_fac = 0.0f;
  735. float yaw_fac = 0.0f;
  736. // find maximum roll, pitch and yaw factors
  737. for (uint8_t i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) {
  738. if (motor_enabled[i]) {
  739. if (roll_fac < fabsf(_roll_factor[i])) {
  740. roll_fac = fabsf(_roll_factor[i]);
  741. }
  742. if (pitch_fac < fabsf(_pitch_factor[i])) {
  743. pitch_fac = fabsf(_pitch_factor[i]);
  744. }
  745. if (yaw_fac < fabsf(_yaw_factor[i])) {
  746. yaw_fac = fabsf(_yaw_factor[i]);
  747. }
  748. }
  749. }
  750. // scale factors back to -0.5 to +0.5 for each axis
  751. for (uint8_t i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) {
  752. if (motor_enabled[i]) {
  753. if (!is_zero(roll_fac)) {
  754. _roll_factor[i] = 0.5f * _roll_factor[i] / roll_fac;
  755. }
  756. if (!is_zero(pitch_fac)) {
  757. _pitch_factor[i] = 0.5f * _pitch_factor[i] / pitch_fac;
  758. }
  759. if (!is_zero(yaw_fac)) {
  760. _yaw_factor[i] = 0.5f * _yaw_factor[i] / yaw_fac;
  761. }
  762. }
  763. }
  764. }
  765. /*
  766. call vehicle supplied thrust compensation if set. This allows
  767. vehicle code to compensate for vehicle specific motor arrangements
  768. such as tiltrotors or tiltwings
  769. */
  770. void AP_MotorsMatrix::thrust_compensation(void)
  771. {
  772. if (_thrust_compensation_callback) {
  773. _thrust_compensation_callback(_thrust_rpyt_out, AP_MOTORS_MAX_NUM_MOTORS);
  774. }
  775. }