uncrustify libraries/AP_Motors/AP_MotorsHeli.cpp

This commit is contained in:
uncrustify 2012-08-21 19:19:52 -07:00 committed by Pat Hickey
parent 4189870bfb
commit 24943e0ea7
1 changed files with 469 additions and 469 deletions

View File

@ -1,12 +1,12 @@
/*
AP_MotorsHeli.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_MotorsHeli.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_MotorsHeli.h"
@ -182,7 +182,7 @@ void AP_MotorsHeli::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_MotorsHeli::enable()
{
// enable output channels
@ -226,7 +226,7 @@ void AP_MotorsHeli::output_armed()
// output_disarmed - sends commands to the motors
void AP_MotorsHeli::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;
@ -512,8 +512,8 @@ void AP_MotorsHeli::rsc_control()
switch ( rsc_mode ) {
case AP_MOTORSHELI_RSC_MODE_CH8_PASSTHROUGH:
if( armed() && _rc_8->control_in > 10 ){
if (rsc_ramp < rsc_ramp_up_rate){
if( armed() && _rc_8->control_in > 10 ) {
if (rsc_ramp < rsc_ramp_up_rate) {
rsc_ramp++;
rsc_output = map(rsc_ramp, 0, rsc_ramp_up_rate, 1000, _rc_8->control_in);
} else {
@ -527,8 +527,8 @@ void AP_MotorsHeli::rsc_control()
case AP_MOTORSHELI_RSC_MODE_EXT_GOV:
if( armed() && _rc_throttle->control_in > 10){
if (rsc_ramp < rsc_ramp_up_rate){
if( armed() && _rc_throttle->control_in > 10) {
if (rsc_ramp < rsc_ramp_up_rate) {
rsc_ramp++;
rsc_output = map(rsc_ramp, 0, rsc_ramp_up_rate, 1000, ext_gov_setpoint);
} else {
@ -536,7 +536,7 @@ void AP_MotorsHeli::rsc_control()
}
} else {
rsc_ramp--; //Return RSC Ramp to 0 slowly, allowing for "warm restart"
if (rsc_ramp < 0){
if (rsc_ramp < 0) {
rsc_ramp = 0;
}
rsc_output = 1000; //Just to be sure RSC output is 0