mirror of https://github.com/ArduPilot/ardupilot
Sub: initialize pwm input on control channels to 1500 instead of 0
This commit is contained in:
parent
dcc96a5705
commit
2cb2633764
|
@ -61,6 +61,15 @@ void Sub::init_rc_in()
|
|||
// set default dead zones
|
||||
default_dead_zones();
|
||||
|
||||
// initialize rc input to 1500 on control channels (rather than 0)
|
||||
for(int i = 0; i < 7; i++) {
|
||||
if(i == 4) {
|
||||
hal.rcin->set_override(i, 1100); // Channel 5 mode selection
|
||||
} else {
|
||||
hal.rcin->set_override(i, 1500);
|
||||
}
|
||||
}
|
||||
|
||||
// initialise throttle_zero flag
|
||||
ap.throttle_zero = true;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue