APM:Libraries
AP_Motors6DOF.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_Motors6DOF.cpp - ArduSub motors library
18  */
19 
21 #include <AP_HAL/AP_HAL.h>
22 #include "AP_Motors6DOF.h"
23 
24 extern const AP_HAL::HAL& hal;
25 
26 // parameters for the motor class
29  // @Param: 1_DIRECTION
30  // @DisplayName: Motor normal or reverse
31  // @Description: Used to change motor rotation directions without changing wires
32  // @Values: 1:normal,-1:reverse
33  // @User: Standard
34  AP_GROUPINFO("1_DIRECTION", 1, AP_Motors6DOF, _motor_reverse[0], 1),
35 
36  // @Param: 2_DIRECTION
37  // @DisplayName: Motor normal or reverse
38  // @Description: Used to change motor rotation directions without changing wires
39  // @Values: 1:normal,-1:reverse
40  // @User: Standard
41  AP_GROUPINFO("2_DIRECTION", 2, AP_Motors6DOF, _motor_reverse[1], 1),
42 
43  // @Param: 3_DIRECTION
44  // @DisplayName: Motor normal or reverse
45  // @Description: Used to change motor rotation directions without changing wires
46  // @Values: 1:normal,-1:reverse
47  // @User: Standard
48  AP_GROUPINFO("3_DIRECTION", 3, AP_Motors6DOF, _motor_reverse[2], 1),
49 
50  // @Param: 4_DIRECTION
51  // @DisplayName: Motor normal or reverse
52  // @Description: Used to change motor rotation directions without changing wires
53  // @Values: 1:normal,-1:reverse
54  // @User: Standard
55  AP_GROUPINFO("4_DIRECTION", 4, AP_Motors6DOF, _motor_reverse[3], 1),
56 
57  // @Param: 5_DIRECTION
58  // @DisplayName: Motor normal or reverse
59  // @Description: Used to change motor rotation directions without changing wires
60  // @Values: 1:normal,-1:reverse
61  // @User: Standard
62  AP_GROUPINFO("5_DIRECTION", 5, AP_Motors6DOF, _motor_reverse[4], 1),
63 
64  // @Param: 6_DIRECTION
65  // @DisplayName: Motor normal or reverse
66  // @Description: Used to change motor rotation directions without changing wires
67  // @Values: 1:normal,-1:reverse
68  // @User: Standard
69  AP_GROUPINFO("6_DIRECTION", 6, AP_Motors6DOF, _motor_reverse[5], 1),
70 
71  // @Param: 7_DIRECTION
72  // @DisplayName: Motor normal or reverse
73  // @Description: Used to change motor rotation directions without changing wires
74  // @Values: 1:normal,-1:reverse
75  // @User: Standard
76  AP_GROUPINFO("7_DIRECTION", 7, AP_Motors6DOF, _motor_reverse[6], 1),
77 
78  // @Param: 8_DIRECTION
79  // @DisplayName: Motor normal or reverse
80  // @Description: Used to change motor rotation directions without changing wires
81  // @Values: 1:normal,-1:reverse
82  // @User: Standard
83  AP_GROUPINFO("8_DIRECTION", 8, AP_Motors6DOF, _motor_reverse[7], 1),
84 
85  // @Param: FV_CPLNG_K
86  // @DisplayName: Forward/vertical to pitch decoupling factor
87  // @Description: Used to decouple pitch from forward/vertical motion. 0 to disable, 1.2 normal
88  // @Range: 0.0 1.5
89  // @Increment: 0.1
90  // @User: Standard
91  AP_GROUPINFO("FV_CPLNG_K", 9, AP_Motors6DOF, _forwardVerticalCouplingFactor, 1.0),
92 
93  // @Param: 9_DIRECTION
94  // @DisplayName: Motor normal or reverse
95  // @Description: Used to change motor rotation directions without changing wires
96  // @Values: 1:normal,-1:reverse
97  // @User: Standard
98  AP_GROUPINFO("9_DIRECTION", 10, AP_Motors6DOF, _motor_reverse[8], 1),
99 
100  // @Param: 10_DIRECTION
101  // @DisplayName: Motor normal or reverse
102  // @Description: Used to change motor rotation directions without changing wires
103  // @Values: 1:normal,-1:reverse
104  // @User: Standard
105  AP_GROUPINFO("10_DIRECTION", 11, AP_Motors6DOF, _motor_reverse[9], 1),
106 
107  // @Param: 11_DIRECTION
108  // @DisplayName: Motor normal or reverse
109  // @Description: Used to change motor rotation directions without changing wires
110  // @Values: 1:normal,-1:reverse
111  // @User: Standard
112  AP_GROUPINFO("11_DIRECTION", 12, AP_Motors6DOF, _motor_reverse[10], 1),
113 
114  // @Param: 12_DIRECTION
115  // @DisplayName: Motor normal or reverse
116  // @Description: Used to change motor rotation directions without changing wires
117  // @Values: 1:normal,-1:reverse
118  // @User: Standard
119  AP_GROUPINFO("12_DIRECTION", 13, AP_Motors6DOF, _motor_reverse[11], 1),
120 
122 };
123 
125 {
126  // remove existing motors
127  for (int8_t i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
128  remove_motor(i);
129  }
130 
131  // hard coded config for supported frames
132  switch ((sub_frame_t)frame_class) {
133  // Motor # Roll Factor Pitch Factor Yaw Factor Throttle Factor Forward Factor Lateral Factor Testing Order
134  case SUB_FRAME_BLUEROV1:
135  add_motor_raw_6dof(AP_MOTORS_MOT_1, 0, 0, -1.0f, 0, 1.0f, 0, 1);
136  add_motor_raw_6dof(AP_MOTORS_MOT_2, 0, 0, 1.0f, 0, 1.0f, 0, 2);
137  add_motor_raw_6dof(AP_MOTORS_MOT_3, -0.5f, 0.5f, 0, 0.45f, 0, 0, 3);
138  add_motor_raw_6dof(AP_MOTORS_MOT_4, 0.5f, 0.5f, 0, 0.45f, 0, 0, 4);
139  add_motor_raw_6dof(AP_MOTORS_MOT_5, 0, -1.0f, 0, 1.0f, 0, 0, 5);
140  add_motor_raw_6dof(AP_MOTORS_MOT_6, -0.25f, 0, 0, 0, 0, 1.0f, 6);
141  break;
142 
144  add_motor_raw_6dof(AP_MOTORS_MOT_1, 1.0f, 1.0f, 0, 1.0f, 0, 0, 1);
145  add_motor_raw_6dof(AP_MOTORS_MOT_2, 0, 0, 1.0f, 0, 1.0f, 0, 2);
146  add_motor_raw_6dof(AP_MOTORS_MOT_3, 1.0f, -1.0f, 0, 1.0f, 0, 0, 3);
147  add_motor_raw_6dof(AP_MOTORS_MOT_4, 0, 0, 0, 0, 0, 1.0f, 4);
148  add_motor_raw_6dof(AP_MOTORS_MOT_5, 0, 0, 0, 0, 0, 1.0f, 5);
149  add_motor_raw_6dof(AP_MOTORS_MOT_6, -1.0f, 1.0f, 0, 1.0f, 0, 0, 6);
150  add_motor_raw_6dof(AP_MOTORS_MOT_7, 0, 0, -1.0f, 0, 1.0f, 0, 7);
151  add_motor_raw_6dof(AP_MOTORS_MOT_8, -1.0f, -1.0f, 0, 1.0f, 0, 0, 8);
152  break;
153 
155  add_motor_raw_6dof(AP_MOTORS_MOT_1, 0, 0, 1.0f, 0, -1.0f, 1.0f, 1);
156  add_motor_raw_6dof(AP_MOTORS_MOT_2, 0, 0, -1.0f, 0, -1.0f, -1.0f, 2);
157  add_motor_raw_6dof(AP_MOTORS_MOT_3, 0, 0, -1.0f, 0, 1.0f, 1.0f, 3);
158  add_motor_raw_6dof(AP_MOTORS_MOT_4, 0, 0, 1.0f, 0, 1.0f, -1.0f, 4);
159  add_motor_raw_6dof(AP_MOTORS_MOT_5, 1.0f, -1.0f, 0, -1.0f, 0, 0, 5);
160  add_motor_raw_6dof(AP_MOTORS_MOT_6, -1.0f, -1.0f, 0, -1.0f, 0, 0, 6);
161  add_motor_raw_6dof(AP_MOTORS_MOT_7, 1.0f, 1.0f, 0, -1.0f, 0, 0, 7);
162  add_motor_raw_6dof(AP_MOTORS_MOT_8, -1.0f, 1.0f, 0, -1.0f, 0, 0, 8);
163  break;
164 
165  case SUB_FRAME_VECTORED:
166  add_motor_raw_6dof(AP_MOTORS_MOT_1, 0, 0, 1.0f, 0, -1.0f, 1.0f, 1);
167  add_motor_raw_6dof(AP_MOTORS_MOT_2, 0, 0, -1.0f, 0, -1.0f, -1.0f, 2);
168  add_motor_raw_6dof(AP_MOTORS_MOT_3, 0, 0, -1.0f, 0, 1.0f, 1.0f, 3);
169  add_motor_raw_6dof(AP_MOTORS_MOT_4, 0, 0, 1.0f, 0, 1.0f, -1.0f, 4);
170  add_motor_raw_6dof(AP_MOTORS_MOT_5, 1.0f, 0, 0, -1.0f, 0, 0, 5);
171  add_motor_raw_6dof(AP_MOTORS_MOT_6, -1.0f, 0, 0, -1.0f, 0, 0, 6);
172  break;
173 
174  case SUB_FRAME_CUSTOM:
175  // Put your custom motor setup here
176  //break;
177 
181  default:
182  add_motor_raw_6dof(AP_MOTORS_MOT_1, 0, 0, -1.0f, 0, 1.0f, 0, 1);
183  add_motor_raw_6dof(AP_MOTORS_MOT_2, 0, 0, 1.0f, 0, 1.0f, 0, 2);
184  add_motor_raw_6dof(AP_MOTORS_MOT_3, 0, 0, 0, -1.0f, 0, 0, 3);
185  add_motor_raw_6dof(AP_MOTORS_MOT_4, 0, 0, 0, -1.0f, 0, 0, 4);
186  add_motor_raw_6dof(AP_MOTORS_MOT_5, 0, 0, 0, 0, 0, 1.0f, 5);
187  break;
188  }
189 }
190 
191 void AP_Motors6DOF::add_motor_raw_6dof(int8_t motor_num, float roll_fac, float pitch_fac, float yaw_fac, float throttle_fac, float forward_fac, float lat_fac, uint8_t testing_order)
192 {
193  //Parent takes care of enabling output and setting up masks
194  add_motor_raw(motor_num, roll_fac, pitch_fac, yaw_fac, testing_order);
195 
196  //These are additional parameters for an ROV
197  _throttle_factor[motor_num] = throttle_fac;
198  _forward_factor[motor_num] = forward_fac;
199  _lateral_factor[motor_num] = lat_fac;
200 }
201 
202 // output_min - sends minimum values out to the motors
204 {
205  int8_t i;
206 
207  // set limits flags
208  limit.roll_pitch = true;
209  limit.yaw = true;
210  limit.throttle_lower = false;
211  limit.throttle_upper = false;
212 
213  // fill the motor_out[] array for HIL use and send minimum value to each motor
214  // ToDo find a field to store the minimum pwm instead of hard coding 1500
215  for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
216  if (motor_enabled[i]) {
217  rc_write(i, 1500);
218  }
219  }
220 }
221 
222 int16_t AP_Motors6DOF::calc_thrust_to_pwm(float thrust_in) const
223 {
224  return constrain_int16(1500 + thrust_in * 400, _throttle_radio_min, _throttle_radio_max);
225 }
226 
228 {
229  int8_t i;
230  int16_t motor_out[AP_MOTORS_MAX_NUM_MOTORS]; // final pwm values sent to the motor
231 
232  switch (_spool_mode) {
233  case SHUT_DOWN:
234  // sends minimum values out to the motors
235  // set motor output based on thrust requests
236  for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
237  if (motor_enabled[i]) {
238  motor_out[i] = 1500;
239  }
240  }
241  break;
242  case SPIN_WHEN_ARMED:
243  // sends output to motors when armed but not flying
244  for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
245  if (motor_enabled[i]) {
246  motor_out[i] = 1500;
247  }
248  }
249  break;
250  case SPOOL_UP:
251  case THROTTLE_UNLIMITED:
252  case SPOOL_DOWN:
253  // set motor output based on thrust requests
254  for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
255  if (motor_enabled[i]) {
256  motor_out[i] = calc_thrust_to_pwm(_thrust_rpyt_out[i]);
257  }
258  }
259  break;
260  }
261 
262  // send output to each motor
263  for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
264  if (motor_enabled[i]) {
265  rc_write(i, motor_out[i]);
266  }
267  }
268 }
269 
271 {
272  return 1.0f;
273 }
274 
275 // output_armed - sends commands to the motors
276 // includes new scaling stability patch
277 // TODO pull code that is common to output_armed_not_stabilizing into helper functions
278 // ToDo calculate headroom for rpy to be added for stabilization during full throttle/forward/lateral commands
280 {
285  } else {
286  uint8_t i; // general purpose counter
287  float roll_thrust; // roll thrust input value, +/- 1.0
288  float pitch_thrust; // pitch thrust input value, +/- 1.0
289  float yaw_thrust; // yaw thrust input value, +/- 1.0
290  float throttle_thrust; // throttle thrust input value, +/- 1.0
291  float forward_thrust; // forward thrust input value, +/- 1.0
292  float lateral_thrust; // lateral thrust input value, +/- 1.0
293 
294  roll_thrust = _roll_in;
295  pitch_thrust = _pitch_in;
296  yaw_thrust = _yaw_in;
297  throttle_thrust = get_throttle_bidirectional();
298  forward_thrust = _forward_in;
299  lateral_thrust = _lateral_in;
300 
301  float rpy_out[AP_MOTORS_MAX_NUM_MOTORS]; // buffer so we don't have to multiply coefficients multiple times.
302  float linear_out[AP_MOTORS_MAX_NUM_MOTORS]; // 3 linear DOF mix for each motor
303 
304  // initialize limits flags
305  limit.roll_pitch = false;
306  limit.yaw = false;
307  limit.throttle_lower = false;
308  limit.throttle_upper = false;
309 
310  // sanity check throttle is above zero and below current limited throttle
311  if (throttle_thrust <= -_throttle_thrust_max) {
312  throttle_thrust = -_throttle_thrust_max;
313  limit.throttle_lower = true;
314  }
315  if (throttle_thrust >= _throttle_thrust_max) {
316  throttle_thrust = _throttle_thrust_max;
317  limit.throttle_upper = true;
318  }
319 
320  // calculate roll, pitch and yaw for each motor
321  for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
322  if (motor_enabled[i]) {
323  rpy_out[i] = roll_thrust * _roll_factor[i] +
324  pitch_thrust * _pitch_factor[i] +
325  yaw_thrust * _yaw_factor[i];
326 
327  }
328  }
329 
330  // calculate linear command for each motor
331  // linear factors should be 0.0 or 1.0 for now
332  for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
333  if (motor_enabled[i]) {
334  linear_out[i] = throttle_thrust * _throttle_factor[i] +
335  forward_thrust * _forward_factor[i] +
336  lateral_thrust * _lateral_factor[i];
337  }
338  }
339 
340  // Calculate final output for each motor
341  for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
342  if (motor_enabled[i]) {
343  _thrust_rpyt_out[i] = constrain_float(_motor_reverse[i]*(rpy_out[i] + linear_out[i]),-1.0f,1.0f);
344  }
345  }
346  }
347 
349 
350  // Current limiting
351  if (_batt_current_max <= 0.0f || !battery.has_current()) {
352  return;
353  }
354 
355  float _batt_current = battery.current_amps();
356 
357  float _batt_current_delta = _batt_current - _batt_current_last;
358 
359  float loop_interval = 1.0f/_loop_rate;
360 
361  float _current_change_rate = _batt_current_delta / loop_interval;
362 
363  float predicted_current = _batt_current + (_current_change_rate * loop_interval * 5);
364 
365  float batt_current_ratio = _batt_current/_batt_current_max;
366 
367  float predicted_current_ratio = predicted_current/_batt_current_max;
368  _batt_current_last = _batt_current;
369 
370  if (predicted_current > _batt_current_max * 1.5f) {
371  batt_current_ratio = 2.5f;
372  } else if (_batt_current < _batt_current_max && predicted_current > _batt_current_max) {
373  batt_current_ratio = predicted_current_ratio;
374  }
375  _output_limited += (loop_interval/(loop_interval+_batt_current_time_constant)) * (1 - batt_current_ratio);
376 
378 
379  for (uint8_t i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) {
380  if (motor_enabled[i]) {
382  }
383  }
384 }
385 
386 // output_armed - sends commands to the motors
387 // includes new scaling stability patch
388 // TODO pull code that is common to output_armed_not_stabilizing into helper functions
389 // ToDo calculate headroom for rpy to be added for stabilization during full throttle/forward/lateral commands
391 {
392  uint8_t i; // general purpose counter
393  float roll_thrust; // roll thrust input value, +/- 1.0
394  float pitch_thrust; // pitch thrust input value, +/- 1.0
395  float yaw_thrust; // yaw thrust input value, +/- 1.0
396  float throttle_thrust; // throttle thrust input value, +/- 1.0
397  float forward_thrust; // forward thrust input value, +/- 1.0
398  float lateral_thrust; // lateral thrust input value, +/- 1.0
399 
400  roll_thrust = _roll_in;
401  pitch_thrust = _pitch_in;
402  yaw_thrust = _yaw_in;
403  throttle_thrust = get_throttle_bidirectional();
404  forward_thrust = _forward_in;
405  lateral_thrust = _lateral_in;
406 
407  float rpy_out[AP_MOTORS_MAX_NUM_MOTORS]; // buffer so we don't have to multiply coefficients multiple times.
408  float linear_out[AP_MOTORS_MAX_NUM_MOTORS]; // 3 linear DOF mix for each motor
409 
410  // initialize limits flags
411  limit.roll_pitch = false;
412  limit.yaw = false;
413  limit.throttle_lower = false;
414  limit.throttle_upper = false;
415 
416  // sanity check throttle is above zero and below current limited throttle
417  if (throttle_thrust <= -_throttle_thrust_max) {
418  throttle_thrust = -_throttle_thrust_max;
419  limit.throttle_lower = true;
420  }
421 
422  if (throttle_thrust >= _throttle_thrust_max) {
423  throttle_thrust = _throttle_thrust_max;
424  limit.throttle_upper = true;
425  }
426 
427  // calculate roll, pitch and yaw for each motor
428  for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
429  if (motor_enabled[i]) {
430  rpy_out[i] = roll_thrust * _roll_factor[i] +
431  pitch_thrust * _pitch_factor[i] +
432  yaw_thrust * _yaw_factor[i];
433  }
434  }
435 
436  float forward_coupling_limit = 1-_forwardVerticalCouplingFactor*float(fabsf(throttle_thrust));
437  if (forward_coupling_limit < 0) {
438  forward_coupling_limit = 0;
439  }
440  int8_t forward_coupling_direction[] = {-1,-1,1,1,0,0,0,0,0,0,0,0};
441 
442  // calculate linear command for each motor
443  // linear factors should be 0.0 or 1.0 for now
444  for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
445  if (motor_enabled[i]) {
446 
447  float forward_thrust_limited = forward_thrust;
448 
449  // The following statements decouple forward/vertical hydrodynamic coupling on
450  // vectored ROVs. This is done by limiting the maximum output of the "rear" vectored
451  // thruster (where "rear" depends on direction of travel).
452  if (!is_zero(forward_thrust_limited)) {
453  if ((forward_thrust < 0) == (forward_coupling_direction[i] < 0) && forward_coupling_direction[i] != 0) {
454  forward_thrust_limited = constrain_float(forward_thrust, -forward_coupling_limit, forward_coupling_limit);
455  }
456  }
457 
458  linear_out[i] = throttle_thrust * _throttle_factor[i] +
459  forward_thrust_limited * _forward_factor[i] +
460  lateral_thrust * _lateral_factor[i];
461  }
462  }
463 
464  // Calculate final output for each motor
465  for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
466  if (motor_enabled[i]) {
467  _thrust_rpyt_out[i] = constrain_float(_motor_reverse[i]*(rpy_out[i] + linear_out[i]), -1.0f, 1.0f);
468  }
469  }
470 }
471 
472 // Band Aid fix for motor normalization issues.
473 // TODO: find a global solution for managing saturation that works for all vehicles
475 {
476  uint8_t i; // general purpose counter
477  float roll_thrust; // roll thrust input value, +/- 1.0
478  float pitch_thrust; // pitch thrust input value, +/- 1.0
479  float yaw_thrust; // yaw thrust input value, +/- 1.0
480  float throttle_thrust; // throttle thrust input value, +/- 1.0
481  float forward_thrust; // forward thrust input value, +/- 1.0
482  float lateral_thrust; // lateral thrust input value, +/- 1.0
483 
484  roll_thrust = _roll_in;
485  pitch_thrust = _pitch_in;
486  yaw_thrust = _yaw_in;
487  throttle_thrust = get_throttle_bidirectional();
488  forward_thrust = _forward_in;
489  lateral_thrust = _lateral_in;
490 
491  float rpt_out[AP_MOTORS_MAX_NUM_MOTORS]; // buffer so we don't have to multiply coefficients multiple times.
492  float yfl_out[AP_MOTORS_MAX_NUM_MOTORS]; // 3 linear DOF mix for each motor
493  float rpt_max;
494  float yfl_max;
495 
496  // initialize limits flags
497  limit.roll_pitch = false;
498  limit.yaw = false;
499  limit.throttle_lower = false;
500  limit.throttle_upper = false;
501 
502  // sanity check throttle is above zero and below current limited throttle
503  if (throttle_thrust <= -_throttle_thrust_max) {
504  throttle_thrust = -_throttle_thrust_max;
505  limit.throttle_lower = true;
506  }
507 
508  if (throttle_thrust >= _throttle_thrust_max) {
509  throttle_thrust = _throttle_thrust_max;
510  limit.throttle_upper = true;
511  }
512 
513  // calculate roll, pitch and Throttle for each motor (only used by vertical thrusters)
514  rpt_max = 1; //Initialized to 1 so that normalization will only occur if value is saturated
515  for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
516  if (motor_enabled[i]) {
517  rpt_out[i] = roll_thrust * _roll_factor[i] +
518  pitch_thrust * _pitch_factor[i] +
519  throttle_thrust * _throttle_factor[i];
520  if (fabsf(rpt_out[i]) > rpt_max) {
521  rpt_max = fabsf(rpt_out[i]);
522  }
523  }
524  }
525 
526  // calculate linear/yaw command for each motor (only used for translational thrusters)
527  // linear factors should be 0.0 or 1.0 for now
528  yfl_max = 1; //Initialized to 1 so that normalization will only occur if value is saturated
529  for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
530  if (motor_enabled[i]) {
531  yfl_out[i] = yaw_thrust * _yaw_factor[i] +
532  forward_thrust * _forward_factor[i] +
533  lateral_thrust * _lateral_factor[i];
534  if (fabsf(yfl_out[i]) > yfl_max) {
535  yfl_max = fabsf(yfl_out[i]);
536  }
537  }
538  }
539 
540  // Calculate final output for each motor and normalize if necessary
541  for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
542  if (motor_enabled[i]) {
543  _thrust_rpyt_out[i] = constrain_float(_motor_reverse[i]*(rpt_out[i]/rpt_max + yfl_out[i]/yfl_max),-1.0f,1.0f);
544  }
545  }
546 }
Motor control class for ROVs with direct control over 6DOF (or fewer) in movement.
float _pitch_factor[AP_MOTORS_MAX_NUM_MOTORS]
void remove_motor(int8_t motor_num)
motor_frame_class _last_frame_class
float _yaw_factor[AP_MOTORS_MAX_NUM_MOTORS]
#define AP_MOTORS_MOT_8
int16_t constrain_int16(const int16_t amt, const int16_t low, const int16_t high)
Definition: AP_Math.h:147
#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)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
float _forward_in
float _forward_factor[AP_MOTORS_MAX_NUM_MOTORS]
Definition: AP_Motors6DOF.h:63
#define AP_MOTORS_MOT_1
#define AP_MOTORS_MOT_2
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
AP_Float _forwardVerticalCouplingFactor
Definition: AP_Motors6DOF.h:60
struct AP_Motors::AP_Motors_limit limit
void add_motor_raw_6dof(int8_t motor_num, float roll_fac, float pitch_fac, float yaw_fac, float climb_fac, float forward_fac, float lat_fac, uint8_t testing_order)
float _batt_current_last
Definition: AP_Motors6DOF.h:68
float _output_limited
Definition: AP_Motors6DOF.h:67
float get_current_limit_max_throttle() override
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_Motors6DOF.h:45
float _lateral_in
float get_throttle_bidirectional() const
void output_armed_stabilizing() override
int16_t calc_thrust_to_pwm(float thrust_in) const
uint16_t _loop_rate
bool motor_enabled[AP_MOTORS_MAX_NUM_MOTORS]
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define f(i)
void setup_motors(motor_frame_class frame_class, motor_frame_type frame_type) override
bool has_current(uint8_t instance) const
has_current - returns true if battery monitor instance provides current info
void output_to_motors() override
float _lateral_factor[AP_MOTORS_MAX_NUM_MOTORS]
Definition: AP_Motors6DOF.h:64
float current_amps(uint8_t instance) const
current_amps - returns the instantaneous current draw in amperes
#define AP_MOTORS_MOT_6
#define AP_MOTORS_MOT_3
virtual void rc_write(uint8_t chan, uint16_t pwm)
AP_BattMonitor & battery()
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
#define AP_NESTEDGROUPINFO(clazz, idx)
Definition: AP_Param.h:105
AP_Int8 _motor_reverse[AP_MOTORS_MAX_NUM_MOTORS]
Definition: AP_Motors6DOF.h:59
void output_min() override
spool_up_down_mode _spool_mode
void output_armed_stabilizing_vectored()
#define AP_MOTORS_MOT_5
#define AP_MOTORS_MAX_NUM_MOTORS
void output_armed_stabilizing_vectored_6dof()
float _throttle_factor[AP_MOTORS_MAX_NUM_MOTORS]
Definition: AP_Motors6DOF.h:62
#define AP_GROUPEND
Definition: AP_Param.h:121