Browse Source

RC_Channel: updates for new AP_Param API

master
Andrew Tridgell 12 years ago
parent
commit
4aa16303ed
  1. 4
      libraries/RC_Channel/RC_Channel.h
  2. 1
      libraries/RC_Channel/RC_Channel_aux.h

4
libraries/RC_Channel/RC_Channel.h

@ -29,9 +29,7 @@ public: @@ -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

1
libraries/RC_Channel/RC_Channel_aux.h

@ -21,6 +21,7 @@ public: @@ -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…
Cancel
Save