mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Rover: if statements is simple.
This commit is contained in:
parent
fd87a4f180
commit
d620efbcb7
@ -51,12 +51,12 @@ void Rover::read_control_switch()
|
|||||||
uint8_t Rover::readSwitch(void){
|
uint8_t Rover::readSwitch(void){
|
||||||
uint16_t pulsewidth = hal.rcin->read(g.mode_channel - 1);
|
uint16_t pulsewidth = hal.rcin->read(g.mode_channel - 1);
|
||||||
if (pulsewidth <= 900 || pulsewidth >= 2200) return 255; // This is an error condition
|
if (pulsewidth <= 900 || pulsewidth >= 2200) return 255; // This is an error condition
|
||||||
if (pulsewidth > 1230 && pulsewidth <= 1360) return 1;
|
if (pulsewidth <= 1230) return 0;
|
||||||
if (pulsewidth > 1360 && pulsewidth <= 1490) return 2;
|
if (pulsewidth <= 1360) return 1;
|
||||||
if (pulsewidth > 1490 && pulsewidth <= 1620) return 3;
|
if (pulsewidth <= 1490) return 2;
|
||||||
if (pulsewidth > 1620 && pulsewidth <= 1749) return 4; // Software Manual
|
if (pulsewidth <= 1620) return 3;
|
||||||
if (pulsewidth >= 1750) return 5; // Hardware Manual
|
if (pulsewidth <= 1749) return 4; // Software Manual
|
||||||
return 0;
|
return 5; // Hardware Manual
|
||||||
}
|
}
|
||||||
|
|
||||||
void Rover::reset_control_switch()
|
void Rover::reset_control_switch()
|
||||||
|
Loading…
Reference in New Issue
Block a user