RC_Channel: updates for new AP_Param API

This commit is contained in:
Andrew Tridgell 2012-12-13 08:47:22 +11:00
parent c064becf28
commit 4aa16303ed
2 changed files with 2 additions and 3 deletions

View File

@ -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

View File

@ -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