mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 01:28:29 -04:00
uncrustify ArduPlane/radio.pde
This commit is contained in:
parent
d5767ef817
commit
43991712be
@ -75,7 +75,7 @@ static void read_radio()
|
||||
ch1_temp = APM_RC.InputCh(CH_ROLL);
|
||||
ch2_temp = APM_RC.InputCh(CH_PITCH);
|
||||
|
||||
if(g.mix_mode == 0){
|
||||
if(g.mix_mode == 0) {
|
||||
g.channel_roll.set_pwm(ch1_temp);
|
||||
g.channel_pitch.set_pwm(ch2_temp);
|
||||
}else{
|
||||
@ -106,11 +106,11 @@ static void read_radio()
|
||||
}
|
||||
|
||||
/*
|
||||
Serial.printf_P(PSTR("OUT 1: %d\t2: %d\t3: %d\t4: %d \n"),
|
||||
(int)g.rc_1.control_in,
|
||||
(int)g.rc_2.control_in,
|
||||
(int)g.rc_3.control_in,
|
||||
(int)g.rc_4.control_in);
|
||||
* Serial.printf_P(PSTR("OUT 1: %d\t2: %d\t3: %d\t4: %d \n"),
|
||||
* (int)g.rc_1.control_in,
|
||||
* (int)g.rc_2.control_in,
|
||||
* (int)g.rc_3.control_in,
|
||||
* (int)g.rc_4.control_in);
|
||||
*/
|
||||
}
|
||||
|
||||
@ -129,30 +129,30 @@ static void control_failsafe(uint16_t pwm)
|
||||
|
||||
//Check for failsafe and debounce funky reads
|
||||
} else if (g.throttle_fs_enabled) {
|
||||
if (pwm < (unsigned)g.throttle_fs_value){
|
||||
if (pwm < (unsigned)g.throttle_fs_value) {
|
||||
// we detect a failsafe from radio
|
||||
// throttle has dropped below the mark
|
||||
failsafeCounter++;
|
||||
if (failsafeCounter == 9){
|
||||
if (failsafeCounter == 9) {
|
||||
gcs_send_text_fmt(PSTR("MSG FS ON %u"), (unsigned)pwm);
|
||||
}else if(failsafeCounter == 10) {
|
||||
ch3_failsafe = true;
|
||||
}else if (failsafeCounter > 10){
|
||||
}else if (failsafeCounter > 10) {
|
||||
failsafeCounter = 11;
|
||||
}
|
||||
|
||||
}else if(failsafeCounter > 0){
|
||||
}else if(failsafeCounter > 0) {
|
||||
// we are no longer in failsafe condition
|
||||
// but we need to recover quickly
|
||||
failsafeCounter--;
|
||||
if (failsafeCounter > 3){
|
||||
if (failsafeCounter > 3) {
|
||||
failsafeCounter = 3;
|
||||
}
|
||||
if (failsafeCounter == 1){
|
||||
if (failsafeCounter == 1) {
|
||||
gcs_send_text_fmt(PSTR("MSG FS OFF %u"), (unsigned)pwm);
|
||||
}else if(failsafeCounter == 0) {
|
||||
ch3_failsafe = false;
|
||||
}else if (failsafeCounter <0){
|
||||
}else if (failsafeCounter <0) {
|
||||
failsafeCounter = -1;
|
||||
}
|
||||
}
|
||||
@ -164,7 +164,7 @@ static void trim_control_surfaces()
|
||||
read_radio();
|
||||
// Store control surface trim values
|
||||
// ---------------------------------
|
||||
if(g.mix_mode == 0){
|
||||
if(g.mix_mode == 0) {
|
||||
g.channel_roll.radio_trim = g.channel_roll.radio_in;
|
||||
g.channel_pitch.radio_trim = g.channel_pitch.radio_in;
|
||||
G_RC_AUX(k_aileron)->radio_trim = g_rc_function[RC_Channel_aux::k_aileron]->radio_in; // Second aileron channel
|
||||
@ -196,7 +196,7 @@ static void trim_radio()
|
||||
|
||||
// Store the trim values
|
||||
// ---------------------
|
||||
if(g.mix_mode == 0){
|
||||
if(g.mix_mode == 0) {
|
||||
g.channel_roll.radio_trim = g.channel_roll.radio_in;
|
||||
g.channel_pitch.radio_trim = g.channel_pitch.radio_in;
|
||||
//g.channel_throttle.radio_trim = g.channel_throttle.radio_in;
|
||||
|
Loading…
Reference in New Issue
Block a user