mirror of https://github.com/ArduPilot/ardupilot
RC_Channel:fix code formatting
This commit is contained in:
parent
32a0c8935e
commit
ab6886f056
|
@ -418,12 +418,19 @@ bool RC_Channel::read_6pos_switch(int8_t& position)
|
|||
return false; // This is an error condition
|
||||
}
|
||||
|
||||
if (pulsewidth < 1231) position = 0;
|
||||
else if (pulsewidth < 1361) position = 1;
|
||||
else if (pulsewidth < 1491) position = 2;
|
||||
else if (pulsewidth < 1621) position = 3;
|
||||
else if (pulsewidth < 1750) position = 4;
|
||||
else position = 5;
|
||||
if (pulsewidth < 1231) {
|
||||
position = 0;
|
||||
} else if (pulsewidth < 1361) {
|
||||
position = 1;
|
||||
} else if (pulsewidth < 1491) {
|
||||
position = 2;
|
||||
} else if (pulsewidth < 1621) {
|
||||
position = 3;
|
||||
} else if (pulsewidth < 1750) {
|
||||
position = 4;
|
||||
} else {
|
||||
position = 5;
|
||||
}
|
||||
|
||||
if (!debounce_completed(position)) {
|
||||
return false;
|
||||
|
|
Loading…
Reference in New Issue