APM:Libraries
AP_MotorsMatrix.cpp
Go to the documentation of this file.
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 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 /*
17  * AP_MotorsMatrix.cpp - ArduCopter motors library
18  * Code by RandyMackay. DIYDrones.com
19  *
20  */
21 #include <AP_HAL/AP_HAL.h>
22 #include "AP_MotorsMatrix.h"
23 
24 extern const AP_HAL::HAL& hal;
25 
26 // init
27 void AP_MotorsMatrix::init(motor_frame_class frame_class, motor_frame_type frame_type)
28 {
29  // record requested frame class and type
30  _last_frame_class = frame_class;
31  _last_frame_type = frame_type;
32 
33  // setup the motors
34  setup_motors(frame_class, frame_type);
35 
36  // enable fast channels or instant pwm
38 }
39 
40 // set update rate to motors - a value in hertz
41 void AP_MotorsMatrix::set_update_rate( uint16_t speed_hz )
42 {
43  // record requested speed
44  _speed_hz = speed_hz;
45 
46  uint16_t mask = 0;
47  for (uint8_t i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
48  if (motor_enabled[i]) {
49  mask |= 1U << i;
50  }
51  }
52  rc_set_freq(mask, _speed_hz );
53 }
54 
55 // set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus)
57 {
58  // exit immediately if armed or no change
59  if (armed() || (frame_class == _last_frame_class && _last_frame_type == frame_type)) {
60  return;
61  }
62  _last_frame_class = frame_class;
63  _last_frame_type = frame_type;
64 
65  // setup the motors
66  setup_motors(frame_class, frame_type);
67 
68  // enable fast channels or instant pwm
70 }
71 
73 {
74  int8_t i;
75  int16_t motor_out[AP_MOTORS_MAX_NUM_MOTORS]; // final pwm values sent to the motor
76 
77  switch (_spool_mode) {
78  case SHUT_DOWN: {
79  // sends minimum values out to the motors
80  // set motor output based on thrust requests
81  for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
82  if (motor_enabled[i]) {
84  motor_out[i] = 0;
85  } else {
86  motor_out[i] = get_pwm_output_min();
87  }
88  }
89  }
90  break;
91  }
92  case SPIN_WHEN_ARMED:
93  // sends output to motors when armed but not flying
94  for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
95  if (motor_enabled[i]) {
96  motor_out[i] = calc_spin_up_to_pwm();
97  }
98  }
99  break;
100  case SPOOL_UP:
101  case THROTTLE_UNLIMITED:
102  case SPOOL_DOWN:
103  // set motor output based on thrust requests
104  for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
105  if (motor_enabled[i]) {
106  motor_out[i] = calc_thrust_to_pwm(_thrust_rpyt_out[i]);
107  }
108  }
109  break;
110  }
111 
112  // send output to each motor
113  for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
114  if (motor_enabled[i]) {
115  rc_write(i, motor_out[i]);
116  }
117  }
118 }
119 
120 
121 // get_motor_mask - returns a bitmask of which outputs are being used for motors (1 means being used)
122 // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
124 {
125  uint16_t mask = 0;
126  for (uint8_t i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
127  if (motor_enabled[i]) {
128  mask |= 1U << i;
129  }
130  }
131  return rc_map_mask(mask);
132 }
133 
134 // output_armed - sends commands to the motors
135 // includes new scaling stability patch
137 {
138  uint8_t i; // general purpose counter
139  float roll_thrust; // roll thrust input value, +/- 1.0
140  float pitch_thrust; // pitch thrust input value, +/- 1.0
141  float yaw_thrust; // yaw thrust input value, +/- 1.0
142  float throttle_thrust; // throttle thrust input value, 0.0 - 1.0
143  float throttle_avg_max; // throttle thrust average maximum value, 0.0 - 1.0
144  float throttle_thrust_best_rpy; // throttle providing maximum roll, pitch and yaw range without climbing
145  float rpy_scale = 1.0f; // this is used to scale the roll, pitch and yaw to fit within the motor limits
146  float rpy_low = 0.0f; // lowest motor value
147  float rpy_high = 0.0f; // highest motor value
148  float yaw_allowed = 1.0f; // amount of yaw we can fit in
149  float unused_range; // amount of yaw we can fit in the current channel
150  float thr_adj; // the difference between the pilot's desired throttle and throttle_thrust_best_rpy
151 
152  // apply voltage and air pressure compensation
153  const float compensation_gain = get_compensation_gain();
154  roll_thrust = _roll_in * compensation_gain;
155  pitch_thrust = _pitch_in * compensation_gain;
156  yaw_thrust = _yaw_in * compensation_gain;
157  throttle_thrust = get_throttle() * compensation_gain;
158  throttle_avg_max = _throttle_avg_max * compensation_gain;
159 
160  // sanity check throttle is above zero and below current limited throttle
161  if (throttle_thrust <= 0.0f) {
162  throttle_thrust = 0.0f;
163  limit.throttle_lower = true;
164  }
165  if (throttle_thrust >= _throttle_thrust_max) {
166  throttle_thrust = _throttle_thrust_max;
167  limit.throttle_upper = true;
168  }
169 
170  throttle_avg_max = constrain_float(throttle_avg_max, throttle_thrust, _throttle_thrust_max);
171 
172  // calculate throttle that gives most possible room for yaw which is the lower of:
173  // 1. 0.5f - (rpy_low+rpy_high)/2.0 - this would give the maximum possible margin above the highest motor and below the lowest
174  // 2. the higher of:
175  // a) the pilot's throttle input
176  // b) the point _throttle_rpy_mix between the pilot's input throttle and hover-throttle
177  // Situation #2 ensure we never increase the throttle above hover throttle unless the pilot has commanded this.
178  // 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.
179  // 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)
180  // 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
181 
182  // calculate amount of yaw we can fit into the throttle range
183  // this is always equal to or less than the requested yaw from the pilot or rate controller
184 
185  throttle_thrust_best_rpy = MIN(0.5f, throttle_avg_max);
186 
187  // calculate roll and pitch for each motor
188  // calculate the amount of yaw input that each motor can accept
189  for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
190  if (motor_enabled[i]) {
191  _thrust_rpyt_out[i] = roll_thrust * _roll_factor[i] + pitch_thrust * _pitch_factor[i];
192  if (!is_zero(_yaw_factor[i])){
193  if (yaw_thrust * _yaw_factor[i] > 0.0f) {
194  unused_range = fabsf(MAX(1.0f - (throttle_thrust_best_rpy + _thrust_rpyt_out[i]), 0.0f)/_yaw_factor[i]);
195  if (yaw_allowed > unused_range) {
196  yaw_allowed = unused_range;
197  }
198  } else {
199  unused_range = fabsf(MAX(throttle_thrust_best_rpy + _thrust_rpyt_out[i], 0.0f)/_yaw_factor[i]);
200  if (yaw_allowed > unused_range) {
201  yaw_allowed = unused_range;
202  }
203  }
204  }
205  }
206  }
207 
208  // todo: make _yaw_headroom 0 to 1
209  yaw_allowed = MAX(yaw_allowed, (float)_yaw_headroom/1000.0f);
210 
211  if (fabsf(yaw_thrust) > yaw_allowed) {
212  yaw_thrust = constrain_float(yaw_thrust, -yaw_allowed, yaw_allowed);
213  limit.yaw = true;
214  }
215 
216  // add yaw to intermediate numbers for each motor
217  rpy_low = 0.0f;
218  rpy_high = 0.0f;
219  for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
220  if (motor_enabled[i]) {
221  _thrust_rpyt_out[i] = _thrust_rpyt_out[i] + yaw_thrust * _yaw_factor[i];
222 
223  // record lowest roll+pitch+yaw command
224  if (_thrust_rpyt_out[i] < rpy_low) {
225  rpy_low = _thrust_rpyt_out[i];
226  }
227  // record highest roll+pitch+yaw command
228  if (_thrust_rpyt_out[i] > rpy_high) {
229  rpy_high = _thrust_rpyt_out[i];
230  }
231  }
232  }
233 
234  // check everything fits
235  throttle_thrust_best_rpy = MIN(0.5f - (rpy_low+rpy_high)/2.0, throttle_avg_max);
236  if (is_zero(rpy_low) && is_zero(rpy_high)){
237  rpy_scale = 1.0f;
238  } else if (is_zero(rpy_low)) {
239  rpy_scale = constrain_float((1.0f-throttle_thrust_best_rpy)/rpy_high, 0.0f, 1.0f);
240  } else if (is_zero(rpy_high)) {
241  rpy_scale = constrain_float(-throttle_thrust_best_rpy/rpy_low, 0.0f, 1.0f);
242  } else {
243  rpy_scale = constrain_float(MIN(-throttle_thrust_best_rpy/rpy_low, (1.0f-throttle_thrust_best_rpy)/rpy_high), 0.0f, 1.0f);
244  }
245 
246  // calculate how close the motors can come to the desired throttle
247  thr_adj = throttle_thrust - throttle_thrust_best_rpy;
248  if (rpy_scale < 1.0f){
249  // Full range is being used by roll, pitch, and yaw.
250  limit.roll_pitch = true;
251  limit.yaw = true;
252  if (thr_adj > 0.0f) {
253  limit.throttle_upper = true;
254  }
255  thr_adj = 0.0f;
256  } else {
257  if (thr_adj < -(throttle_thrust_best_rpy+rpy_low)){
258  // Throttle can't be reduced to desired value
259  thr_adj = -(throttle_thrust_best_rpy+rpy_low);
260  } else if (thr_adj > 1.0f - (throttle_thrust_best_rpy+rpy_high)){
261  // Throttle can't be increased to desired value
262  thr_adj = 1.0f - (throttle_thrust_best_rpy+rpy_high);
263  limit.throttle_upper = true;
264  }
265  }
266 
267  // add scaled roll, pitch, constrained yaw and throttle for each motor
268  for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
269  if (motor_enabled[i]) {
270  _thrust_rpyt_out[i] = throttle_thrust_best_rpy + thr_adj + rpy_scale*_thrust_rpyt_out[i];
271  }
272  }
273 
274  // constrain all outputs to 0.0f to 1.0f
275  // test code should be run with these lines commented out as they should not do anything
276  for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
277  if (motor_enabled[i]) {
279  }
280  }
281 }
282 
283 // output_test - spin a motor at the pwm value specified
284 // motor_seq is the motor's sequence number from 1 to the number of motors on the frame
285 // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
286 void AP_MotorsMatrix::output_test(uint8_t motor_seq, int16_t pwm)
287 {
288  // exit immediately if not armed
289  if (!armed()) {
290  return;
291  }
292 
293  // loop through all the possible orders spinning any motors that match that description
294  for (uint8_t i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
295  if (motor_enabled[i] && _test_order[i] == motor_seq) {
296  // turn on this motor
297  rc_write(i, pwm);
298  }
299  }
300 }
301 
302 // add_motor
303 void AP_MotorsMatrix::add_motor_raw(int8_t motor_num, float roll_fac, float pitch_fac, float yaw_fac, uint8_t testing_order)
304 {
305  // ensure valid motor number is provided
306  if( motor_num >= 0 && motor_num < AP_MOTORS_MAX_NUM_MOTORS ) {
307 
308  // increment number of motors if this motor is being newly motor_enabled
309  if( !motor_enabled[motor_num] ) {
310  motor_enabled[motor_num] = true;
311  }
312 
313  // set roll, pitch, thottle factors and opposite motor (for stability patch)
314  _roll_factor[motor_num] = roll_fac;
315  _pitch_factor[motor_num] = pitch_fac;
316  _yaw_factor[motor_num] = yaw_fac;
317 
318  // set order that motor appears in test
319  _test_order[motor_num] = testing_order;
320 
321  // call parent class method
322  add_motor_num(motor_num);
323  }
324 }
325 
326 // add_motor using just position and prop direction - assumes that for each motor, roll and pitch factors are equal
327 void AP_MotorsMatrix::add_motor(int8_t motor_num, float angle_degrees, float yaw_factor, uint8_t testing_order)
328 {
329  add_motor(motor_num, angle_degrees, angle_degrees, yaw_factor, testing_order);
330 }
331 
332 // add_motor using position and prop direction. Roll and Pitch factors can differ (for asymmetrical frames)
333 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)
334 {
336  motor_num,
337  cosf(radians(roll_factor_in_degrees + 90)),
338  cosf(radians(pitch_factor_in_degrees)),
339  yaw_factor,
340  testing_order);
341 }
342 
343 // remove_motor - disabled motor and clears all roll, pitch, throttle factors for this motor
344 void AP_MotorsMatrix::remove_motor(int8_t motor_num)
345 {
346  // ensure valid motor number is provided
347  if( motor_num >= 0 && motor_num < AP_MOTORS_MAX_NUM_MOTORS ) {
348  // disable the motor, set all factors to zero
349  motor_enabled[motor_num] = false;
350  _roll_factor[motor_num] = 0;
351  _pitch_factor[motor_num] = 0;
352  _yaw_factor[motor_num] = 0;
353  }
354 }
355 
357 {
358  // remove existing motors
359  for (int8_t i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
360  remove_motor(i);
361  }
362 
363  bool success = false;
364 
365  switch (frame_class) {
366 
367  case MOTOR_FRAME_QUAD:
368  switch (frame_type) {
374  success = true;
375  break;
376  case MOTOR_FRAME_TYPE_X:
381  success = true;
382  break;
383  case MOTOR_FRAME_TYPE_V:
384  add_motor(AP_MOTORS_MOT_1, 45, 0.7981f, 1);
385  add_motor(AP_MOTORS_MOT_2, -135, 1.0000f, 3);
386  add_motor(AP_MOTORS_MOT_3, -45, -0.7981f, 4);
387  add_motor(AP_MOTORS_MOT_4, 135, -1.0000f, 2);
388  success = true;
389  break;
390  case MOTOR_FRAME_TYPE_H:
391  // H frame set-up - same as X but motors spin in opposite directiSons
396  success = true;
397  break;
399  /*
400  Tested with: Lynxmotion Hunter Vtail 400
401  - inverted rear outward blowing motors (at a 40 degree angle)
402  - should also work with non-inverted rear outward blowing motors
403  - no roll in rear motors
404  - no yaw in front motors
405  - should fly like some mix between a tricopter and X Quadcopter
406 
407  Roll control comes only from the front motors, Yaw control only from the rear motors.
408  Roll & Pitch factor is measured by the angle away from the top of the forward axis to each arm.
409 
410  Note: if we want the front motors to help with yaw,
411  motors 1's yaw factor should be changed to sin(radians(40)). Where "40" is the vtail angle
412  motors 3's yaw factor should be changed to -sin(radians(40))
413  */
414  add_motor(AP_MOTORS_MOT_1, 60, 60, 0, 1);
416  add_motor(AP_MOTORS_MOT_3, -60, -60, 0, 4);
418  success = true;
419  break;
421  /*
422  The A-Shaped VTail is the exact same as a V-Shaped VTail, with one difference:
423  - The Yaw factors are reversed, because the rear motors are facing different directions
424 
425  With V-Shaped VTails, the props make a V-Shape when spinning, but with
426  A-Shaped VTails, the props make an A-Shape when spinning.
427  - Rear thrust on a V-Shaped V-Tail Quad is outward
428  - Rear thrust on an A-Shaped V-Tail Quad is inward
429 
430  Still functions the same as the V-Shaped VTail mixing below:
431  - Yaw control is entirely in the rear motors
432  - Roll is is entirely in the front motors
433  */
434  add_motor(AP_MOTORS_MOT_1, 60, 60, 0, 1);
436  add_motor(AP_MOTORS_MOT_3, -60, -60, 0, 4);
438  success = true;
439  break;
440  default:
441  // quad frame class does not support this frame type
442  break;
443  }
444  break; // quad
445 
446  case MOTOR_FRAME_HEXA:
447  switch (frame_type) {
455  success = true;
456  break;
457  case MOTOR_FRAME_TYPE_X:
464  success = true;
465  break;
466  default:
467  // hexa frame class does not support this frame type
468  break;
469  }
470  break;
471 
472  case MOTOR_FRAME_OCTA:
473  switch (frame_type) {
483  success = true;
484  break;
485  case MOTOR_FRAME_TYPE_X:
494  success = true;
495  break;
496  case MOTOR_FRAME_TYPE_V:
505  success = true;
506  break;
507  case MOTOR_FRAME_TYPE_H:
516  success = true;
517  break;
518  default:
519  // octa frame class does not support this frame type
520  break;
521  } // octa frame type
522  break;
523 
525  switch (frame_type) {
535  success = true;
536  break;
537  case MOTOR_FRAME_TYPE_X:
546  success = true;
547  break;
548  case MOTOR_FRAME_TYPE_V:
549  add_motor(AP_MOTORS_MOT_1, 45, 0.7981f, 1);
550  add_motor(AP_MOTORS_MOT_2, -45, -0.7981f, 7);
551  add_motor(AP_MOTORS_MOT_3, -135, 1.0000f, 5);
552  add_motor(AP_MOTORS_MOT_4, 135, -1.0000f, 3);
553  add_motor(AP_MOTORS_MOT_5, -45, 0.7981f, 8);
554  add_motor(AP_MOTORS_MOT_6, 45, -0.7981f, 2);
555  add_motor(AP_MOTORS_MOT_7, 135, 1.0000f, 4);
556  add_motor(AP_MOTORS_MOT_8, -135, -1.0000f, 6);
557  success = true;
558  break;
559  case MOTOR_FRAME_TYPE_H:
560  // H frame set-up - same as X but motors spin in opposite directions
569  success = true;
570  break;
571  default:
572  // octaquad frame class does not support this frame type
573  break;
574  }
575  break;
576 
577  case MOTOR_FRAME_DODECAHEXA: {
578  switch (frame_type) {
581  add_motor(AP_MOTORS_MOT_2, 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2); // forward-bottom
582  add_motor(AP_MOTORS_MOT_3, 60, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3); // forward-right-top
583  add_motor(AP_MOTORS_MOT_4, 60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4); // forward-right-bottom
584  add_motor(AP_MOTORS_MOT_5, 120, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5); // back-right-top
585  add_motor(AP_MOTORS_MOT_6, 120, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6); // back-right-bottom
588  add_motor(AP_MOTORS_MOT_9, -120, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 9); // back-left-top
589  add_motor(AP_MOTORS_MOT_10, -120, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 10); // back-left-bottom
590  add_motor(AP_MOTORS_MOT_11, -60, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 11); // forward-left-top
591  add_motor(AP_MOTORS_MOT_12, -60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 12); // forward-left-bottom
592  success = true;
593  break;
594  case MOTOR_FRAME_TYPE_X:
595  add_motor(AP_MOTORS_MOT_1, 30, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1); // forward-right-top
596  add_motor(AP_MOTORS_MOT_2, 30, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2); // forward-right-bottom
599  add_motor(AP_MOTORS_MOT_5, 150, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5); // back-right-top
600  add_motor(AP_MOTORS_MOT_6, 150, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6); // back-right-bottom
601  add_motor(AP_MOTORS_MOT_7, -150, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7); // back-left-top
602  add_motor(AP_MOTORS_MOT_8, -150, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8); // back-left-bottom
605  add_motor(AP_MOTORS_MOT_11, -30, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 11); // forward-left-top
606  add_motor(AP_MOTORS_MOT_12, -30, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 12); // forward-left-bottom
607  success = true;
608  break;
609  default:
610  // dodeca-hexa frame class does not support this frame type
611  break;
612  }}
613  break;
614 
615  case MOTOR_FRAME_Y6:
616  switch (frame_type) {
618  // Y6 motor definition with all top motors spinning clockwise, all bottom motors counter clockwise
625  success = true;
626  break;
628  // Y6 motor layout for FireFlyY6
635  success = true;
636  break;
637  default:
644  success = true;
645  break;
646  }
647  break;
648 
649  default:
650  // matrix doesn't support the configured class
651  break;
652  } // switch frame_class
653 
654  // normalise factors to magnitude 0.5
656 
657  _flags.initialised_ok = success;
658 }
659 
660 // normalizes the roll, pitch and yaw factors so maximum magnitude is 0.5
662 {
663  float roll_fac = 0.0f;
664  float pitch_fac = 0.0f;
665  float yaw_fac = 0.0f;
666 
667  // find maximum roll, pitch and yaw factors
668  for (uint8_t i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
669  if (motor_enabled[i]) {
670  if (roll_fac < fabsf(_roll_factor[i])) {
671  roll_fac = fabsf(_roll_factor[i]);
672  }
673  if (pitch_fac < fabsf(_pitch_factor[i])) {
674  pitch_fac = fabsf(_pitch_factor[i]);
675  }
676  if (yaw_fac < fabsf(_yaw_factor[i])) {
677  yaw_fac = fabsf(_yaw_factor[i]);
678  }
679  }
680  }
681 
682  // scale factors back to -0.5 to +0.5 for each axis
683  for (uint8_t i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
684  if (motor_enabled[i]) {
685  if (!is_zero(roll_fac)) {
686  _roll_factor[i] = 0.5f*_roll_factor[i]/roll_fac;
687  }
688  if (!is_zero(pitch_fac)) {
689  _pitch_factor[i] = 0.5f*_pitch_factor[i]/pitch_fac;
690  }
691  if (!is_zero(yaw_fac)) {
692  _yaw_factor[i] = 0.5f*_yaw_factor[i]/yaw_fac;
693  }
694  }
695  }
696 }
697 
698 
699 /*
700  call vehicle supplied thrust compensation if set. This allows
701  vehicle code to compensate for vehicle specific motor arrangements
702  such as tiltrotors or tiltwings
703 */
705 {
708  }
709 }
float _pitch_factor[AP_MOTORS_MAX_NUM_MOTORS]
void remove_motor(int8_t motor_num)
motor_frame_type _last_frame_type
motor_frame_class _last_frame_class
int16_t get_pwm_output_min() const
float _yaw_factor[AP_MOTORS_MAX_NUM_MOTORS]
virtual void setup_motors(motor_frame_class frame_class, motor_frame_type frame_type)
#define AP_MOTORS_MOT_8
#define AP_MOTORS_MOT_4
#define AP_MOTORS_MOT_7
void add_motor_raw(int8_t motor_num, float roll_fac, float pitch_fac, float yaw_fac, uint8_t testing_order)
#define AP_MOTORS_MOT_1
struct AP_Motors::AP_Motors_flags _flags
void thrust_compensation(void) override
#define AP_MOTORS_MOT_2
#define AP_MOTORS_MATRIX_YAW_FACTOR_CCW
struct AP_Motors::AP_Motors_limit limit
#define AP_MOTORS_MOT_11
uint8_t _test_order[AP_MOTORS_MAX_NUM_MOTORS]
void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type)
static uint16_t pwm
Definition: RCOutput.cpp:20
#define MIN(a, b)
Definition: usb_conf.h:215
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
void output_armed_stabilizing()
void output_test(uint8_t motor_seq, int16_t pwm)
bool armed() const
Motor control class for Matrixcopters.
bool motor_enabled[AP_MOTORS_MAX_NUM_MOTORS]
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define f(i)
void init(motor_frame_class frame_class, motor_frame_type frame_type)
uint16_t get_motor_mask()
uint16_t _speed_hz
#define AP_MOTORS_MOT_6
#define AP_MOTORS_MOT_3
float _throttle_avg_max
void add_motor(int8_t motor_num, float angle_degrees, float yaw_factor, uint8_t testing_order)
virtual void rc_write(uint8_t chan, uint16_t pwm)
float _roll_factor[AP_MOTORS_MAX_NUM_MOTORS]
float _thrust_rpyt_out[AP_MOTORS_MAX_NUM_MOTORS]
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
void set_update_rate(uint16_t speed_hz)
static constexpr float radians(float deg)
Definition: AP_Math.h:158
void add_motor_num(int8_t motor_num)
virtual void rc_set_freq(uint32_t mask, uint16_t freq_hz)
#define AP_MOTORS_MOT_12
spool_up_down_mode _spool_mode
#define AP_MOTORS_MOT_5
int16_t calc_spin_up_to_pwm() const
thrust_compensation_fn_t _thrust_compensation_callback
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
int16_t calc_thrust_to_pwm(float thrust_in) const
float get_throttle() const
#define AP_MOTORS_MOT_10
#define AP_MOTORS_MAX_NUM_MOTORS
virtual uint32_t rc_map_mask(uint32_t mask) const
#define AP_MOTORS_MOT_9
#define AP_MOTORS_MATRIX_YAW_FACTOR_CW