mirror of https://github.com/ArduPilot/ardupilot
RC_Channel: updates for new AP_Param API
This commit is contained in:
parent
c064becf28
commit
4aa16303ed
|
@ -29,9 +29,7 @@ public:
|
|||
RC_Channel(uint8_t ch_out) :
|
||||
_high(1),
|
||||
_ch_out(ch_out) {
|
||||
if (_reverse == 0) {
|
||||
_reverse = 1;
|
||||
}
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
}
|
||||
|
||||
// setup min and max radio values in CLI
|
||||
|
|
|
@ -21,6 +21,7 @@ public:
|
|||
RC_Channel_aux(uint8_t ch_out) :
|
||||
RC_Channel(ch_out)
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
}
|
||||
|
||||
typedef enum
|
||||
|
|
Loading…
Reference in New Issue