uncrustify libraries/AP_Motors/AP_MotorsTri.cpp

This commit is contained in:
uncrustify 2012-08-16 23:20:26 -07:00 committed by Pat Hickey
parent 2712e5357d
commit ecc88f6f8c

View File

@ -1,12 +1,12 @@
/*
AP_MotorsTri.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_MotorsTri.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_MotorsTri.h"
@ -29,7 +29,7 @@ void AP_MotorsTri::set_update_rate( uint16_t speed_hz )
}
}
// enable - starts allowing signals to be sent to motors
// enable - starts allowing signals to be sent to motors
void AP_MotorsTri::enable()
{
// enable output channels
@ -89,19 +89,19 @@ void AP_MotorsTri::output_armed()
motor_out[AP_MOTORS_MOT_4] = _rc_throttle->radio_out - _rc_pitch->pwm_out;
// Tridge's stability patch
if(motor_out[AP_MOTORS_MOT_1] > out_max){
if(motor_out[AP_MOTORS_MOT_1] > out_max) {
motor_out[AP_MOTORS_MOT_2] -= (motor_out[AP_MOTORS_MOT_1] - out_max) >> 1;
motor_out[AP_MOTORS_MOT_4] -= (motor_out[AP_MOTORS_MOT_1] - out_max) >> 1;
motor_out[AP_MOTORS_MOT_1] = out_max;
}
if(motor_out[AP_MOTORS_MOT_2] > out_max){
if(motor_out[AP_MOTORS_MOT_2] > out_max) {
motor_out[AP_MOTORS_MOT_1] -= (motor_out[AP_MOTORS_MOT_2] - out_max) >> 1;
motor_out[AP_MOTORS_MOT_4] -= (motor_out[AP_MOTORS_MOT_2] - out_max) >> 1;
motor_out[AP_MOTORS_MOT_2] = out_max;
}
if(motor_out[AP_MOTORS_MOT_4] > out_max){
if(motor_out[AP_MOTORS_MOT_4] > out_max) {
motor_out[AP_MOTORS_MOT_1] -= (motor_out[AP_MOTORS_MOT_4] - out_max) >> 1;
motor_out[AP_MOTORS_MOT_2] -= (motor_out[AP_MOTORS_MOT_4] - out_max) >> 1;
motor_out[AP_MOTORS_MOT_4] = out_max;
@ -112,14 +112,14 @@ void AP_MotorsTri::output_armed()
motor_out[AP_MOTORS_MOT_2] = max(motor_out[AP_MOTORS_MOT_2], out_min);
motor_out[AP_MOTORS_MOT_4] = max(motor_out[AP_MOTORS_MOT_4], out_min);
#if CUT_MOTORS == ENABLED
#if CUT_MOTORS == ENABLED
// if we are not sending a throttle output, we cut the motors
if(_rc_throttle->servo_out == 0){
if(_rc_throttle->servo_out == 0) {
motor_out[AP_MOTORS_MOT_1] = _rc_throttle->radio_min;
motor_out[AP_MOTORS_MOT_2] = _rc_throttle->radio_min;
motor_out[AP_MOTORS_MOT_4] = _rc_throttle->radio_min;
}
#endif
#endif
// send output to each motor
_rc->OutputCh(_motor_to_channel_map[AP_MOTORS_MOT_1], motor_out[AP_MOTORS_MOT_1]);
@ -146,14 +146,14 @@ void AP_MotorsTri::output_armed()
// output_disarmed - sends commands to the motors
void AP_MotorsTri::output_disarmed()
{
if(_rc_throttle->control_in > 0){
if(_rc_throttle->control_in > 0) {
// we have pushed up the throttle
// remove safety
_auto_armed = true;
}
// fill the motor_out[] array for HIL use
for (unsigned char i = AP_MOTORS_MOT_1; i < AP_MOTORS_MOT_4; i++){
for (unsigned char i = AP_MOTORS_MOT_1; i < AP_MOTORS_MOT_4; i++) {
motor_out[i] = _rc_throttle->radio_min;
}