mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
Rover: control_modes.cpp correct whitespace, remove tabs
This commit is contained in:
parent
597423fffc
commit
5232dce268
@ -7,7 +7,9 @@ void Rover::read_control_switch()
|
||||
|
||||
// If switchPosition = 255 this indicates that the mode control channel input was out of range
|
||||
// If we get this value we do not want to change modes.
|
||||
if(switchPosition == 255) return;
|
||||
if (switchPosition == 255) {
|
||||
return;
|
||||
}
|
||||
|
||||
if (AP_HAL::millis() - failsafe.last_valid_rc_ms > 100) {
|
||||
// only use signals that are less than 0.1s old.
|
||||
@ -23,7 +25,6 @@ void Rover::read_control_switch()
|
||||
if (oldSwitchPosition != switchPosition ||
|
||||
(g.reset_switch_chan != 0 &&
|
||||
hal.rcin->read(g.reset_switch_chan-1) > RESET_SWITCH_CHAN_PWM)) {
|
||||
|
||||
if (switch_debouncer == false) {
|
||||
// this ensures that mode switches only happen if the
|
||||
// switch changes for 2 reads. This prevents momentary
|
||||
@ -43,17 +44,28 @@ void Rover::read_control_switch()
|
||||
}
|
||||
|
||||
switch_debouncer = false;
|
||||
|
||||
}
|
||||
|
||||
uint8_t Rover::readSwitch(void) {
|
||||
uint16_t pulsewidth = hal.rcin->read(g.mode_channel - 1);
|
||||
if (pulsewidth <= 900 || pulsewidth >= 2200) return 255; // This is an error condition
|
||||
if (pulsewidth <= 1230) return 0;
|
||||
if (pulsewidth <= 1360) return 1;
|
||||
if (pulsewidth <= 1490) return 2;
|
||||
if (pulsewidth <= 1620) return 3;
|
||||
if (pulsewidth <= 1749) return 4; // Software Manual
|
||||
if (pulsewidth <= 900 || pulsewidth >= 2200) {
|
||||
return 255; // This is an error condition
|
||||
}
|
||||
if (pulsewidth <= 1230) {
|
||||
return 0;
|
||||
}
|
||||
if (pulsewidth <= 1360) {
|
||||
return 1;
|
||||
}
|
||||
if (pulsewidth <= 1490) {
|
||||
return 2;
|
||||
}
|
||||
if (pulsewidth <= 1620) {
|
||||
return 3;
|
||||
}
|
||||
if (pulsewidth <= 1749) {
|
||||
return 4; // Software Manual
|
||||
}
|
||||
return 5; // Hardware Manual
|
||||
}
|
||||
|
||||
@ -89,7 +101,7 @@ void Rover::read_trim_switch()
|
||||
// if roll is full right store the current location as home
|
||||
init_home();
|
||||
}
|
||||
return;
|
||||
break;
|
||||
|
||||
case LEARNING:
|
||||
case STEERING: {
|
||||
@ -107,10 +119,9 @@ void Rover::read_trim_switch()
|
||||
// save command
|
||||
if (mission.add_cmd(cmd)) {
|
||||
hal.console->printf("Learning waypoint %u", (unsigned) mission.num_commands());
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
}
|
||||
case AUTO:
|
||||
// if SW7 is ON in AUTO = set to RTL
|
||||
set_mode(RTL);
|
||||
|
Loading…
Reference in New Issue
Block a user