mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 16:48:29 -04:00
RC_Channel: ensure _reverse is not 0
this caused the example to fail
This commit is contained in:
parent
8577a0c7a1
commit
bad02cab04
@ -23,6 +23,9 @@ public:
|
|||||||
_filter(false),
|
_filter(false),
|
||||||
_high(1),
|
_high(1),
|
||||||
_ch_out(ch_out) {
|
_ch_out(ch_out) {
|
||||||
|
if (_reverse == 0) {
|
||||||
|
_reverse = 1;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// setup min and max radio values in CLI
|
// setup min and max radio values in CLI
|
||||||
|
Loading…
Reference in New Issue
Block a user