mirror of https://github.com/ArduPilot/ardupilot
RC_Channel.h - small change to store _reverse setting to eeprom
git-svn-id: https://arducopter.googlecode.com/svn/trunk@2528 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
0779971bea
commit
13203fd211
|
@ -28,7 +28,7 @@ class RC_Channel{
|
||||||
radio_max (&_group, 2, 1500, name ? PSTR("MAX") : 0),
|
radio_max (&_group, 2, 1500, name ? PSTR("MAX") : 0),
|
||||||
_high(1),
|
_high(1),
|
||||||
_filter(true),
|
_filter(true),
|
||||||
_reverse(1),
|
_reverse (&_group, 3, 1, name ? PSTR("REV") : 0),
|
||||||
dead_zone(0),
|
dead_zone(0),
|
||||||
scale_output(1.0)
|
scale_output(1.0)
|
||||||
{}
|
{}
|
||||||
|
@ -96,7 +96,7 @@ class RC_Channel{
|
||||||
|
|
||||||
private:
|
private:
|
||||||
bool _filter;
|
bool _filter;
|
||||||
int8_t _reverse;
|
AP_Int8 _reverse;
|
||||||
|
|
||||||
uint8_t _type;
|
uint8_t _type;
|
||||||
int16_t _high;
|
int16_t _high;
|
||||||
|
|
Loading…
Reference in New Issue