mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-03 06:28:32 -04:00
uncrustify libraries/AP_Motors/AP_MotorsMatrix.cpp
This commit is contained in:
parent
21c2609c61
commit
59d64e054a
@ -1,11 +1,11 @@
|
||||
/*
|
||||
AP_MotorsMatrix.cpp - ArduCopter motors library
|
||||
Code by RandyMackay. DIYDrones.com
|
||||
|
||||
This library is free software; you can redistribute it and/or
|
||||
modify it under the terms of the GNU Lesser General Public
|
||||
License as published by the Free Software Foundation; either
|
||||
version 2.1 of the License, or (at your option) any later version.
|
||||
* AP_MotorsMatrix.cpp - ArduCopter motors library
|
||||
* Code by RandyMackay. DIYDrones.com
|
||||
*
|
||||
* This library is free software; you can redistribute it and/or
|
||||
* modify it under the terms of the GNU Lesser General Public
|
||||
* License as published by the Free Software Foundation; either
|
||||
* version 2.1 of the License, or (at your option) any later version.
|
||||
*/
|
||||
|
||||
#include "AP_MotorsMatrix.h"
|
||||
@ -143,11 +143,11 @@ void AP_MotorsMatrix::output_armed()
|
||||
for( i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++ ) {
|
||||
if( motor_enabled[i] ) {
|
||||
/*yaw_contribution = _rc_yaw->pwm_out*_yaw_factor[i];
|
||||
if (yaw_contribution > 0 ){
|
||||
yaw_contribution *= 0.7;
|
||||
}else{
|
||||
yaw_contribution *= 1.42;
|
||||
}*/
|
||||
* if (yaw_contribution > 0 ){
|
||||
* yaw_contribution *= 0.7;
|
||||
* }else{
|
||||
* yaw_contribution *= 1.42;
|
||||
* }*/
|
||||
motor_out[i] = _rc_throttle->radio_out +
|
||||
_rc_roll->pwm_out * _roll_factor[i] +
|
||||
_rc_pitch->pwm_out * _pitch_factor[i] +
|
||||
|
Loading…
Reference in New Issue
Block a user