mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 02:28:29 -04:00
uncrustify libraries/AP_Motors/AP_MotorsMatrix.cpp
This commit is contained in:
parent
21c2609c61
commit
59d64e054a
@ -1,12 +1,12 @@
|
|||||||
/*
|
/*
|
||||||
AP_MotorsMatrix.cpp - ArduCopter motors library
|
* AP_MotorsMatrix.cpp - ArduCopter motors library
|
||||||
Code by RandyMackay. DIYDrones.com
|
* Code by RandyMackay. DIYDrones.com
|
||||||
|
*
|
||||||
This library is free software; you can redistribute it and/or
|
* This library is free software; you can redistribute it and/or
|
||||||
modify it under the terms of the GNU Lesser General Public
|
* modify it under the terms of the GNU Lesser General Public
|
||||||
License as published by the Free Software Foundation; either
|
* License as published by the Free Software Foundation; either
|
||||||
version 2.1 of the License, or (at your option) any later version.
|
* version 2.1 of the License, or (at your option) any later version.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include "AP_MotorsMatrix.h"
|
#include "AP_MotorsMatrix.h"
|
||||||
|
|
||||||
@ -143,11 +143,11 @@ void AP_MotorsMatrix::output_armed()
|
|||||||
for( i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++ ) {
|
for( i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++ ) {
|
||||||
if( motor_enabled[i] ) {
|
if( motor_enabled[i] ) {
|
||||||
/*yaw_contribution = _rc_yaw->pwm_out*_yaw_factor[i];
|
/*yaw_contribution = _rc_yaw->pwm_out*_yaw_factor[i];
|
||||||
if (yaw_contribution > 0 ){
|
* if (yaw_contribution > 0 ){
|
||||||
yaw_contribution *= 0.7;
|
* yaw_contribution *= 0.7;
|
||||||
}else{
|
* }else{
|
||||||
yaw_contribution *= 1.42;
|
* yaw_contribution *= 1.42;
|
||||||
}*/
|
* }*/
|
||||||
motor_out[i] = _rc_throttle->radio_out +
|
motor_out[i] = _rc_throttle->radio_out +
|
||||||
_rc_roll->pwm_out * _roll_factor[i] +
|
_rc_roll->pwm_out * _roll_factor[i] +
|
||||||
_rc_pitch->pwm_out * _pitch_factor[i] +
|
_rc_pitch->pwm_out * _pitch_factor[i] +
|
||||||
@ -172,16 +172,16 @@ void AP_MotorsMatrix::output_armed()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#if CUT_MOTORS == ENABLED
|
#if CUT_MOTORS == ENABLED
|
||||||
// if we are not sending a throttle output, we cut the motors
|
// if we are not sending a throttle output, we cut the motors
|
||||||
if(_rc_throttle->servo_out == 0){
|
if(_rc_throttle->servo_out == 0) {
|
||||||
for( i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++ ) {
|
for( i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++ ) {
|
||||||
if( motor_enabled[i] ) {
|
if( motor_enabled[i] ) {
|
||||||
motor_out[i] = _rc_throttle->radio_min;
|
motor_out[i] = _rc_throttle->radio_min;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// send output to each motor
|
// send output to each motor
|
||||||
for( i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++ ) {
|
for( i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++ ) {
|
||||||
@ -204,7 +204,7 @@ void AP_MotorsMatrix::output_armed()
|
|||||||
// output_disarmed - sends commands to the motors
|
// output_disarmed - sends commands to the motors
|
||||||
void AP_MotorsMatrix::output_disarmed()
|
void AP_MotorsMatrix::output_disarmed()
|
||||||
{
|
{
|
||||||
if(_rc_throttle->control_in > 0){
|
if(_rc_throttle->control_in > 0) {
|
||||||
// we have pushed up the throttle
|
// we have pushed up the throttle
|
||||||
// remove safety for auto pilot
|
// remove safety for auto pilot
|
||||||
_auto_armed = true;
|
_auto_armed = true;
|
||||||
|
Loading…
Reference in New Issue
Block a user