mirror of https://github.com/ArduPilot/ardupilot
changed a bool to uint8_t
git-svn-id: https://arducopter.googlecode.com/svn/trunk@2120 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
5242396e06
commit
8f82de3e11
|
@ -18,6 +18,7 @@
|
|||
#define RC_CHANNEL_RANGE 1
|
||||
#define RC_CHANNEL_ANGLE_RAW 2
|
||||
|
||||
|
||||
// setup the control preferences
|
||||
void
|
||||
RC_Channel::set_range(int low, int high)
|
||||
|
@ -53,10 +54,13 @@ RC_Channel::set_filter(bool filter)
|
|||
{
|
||||
_filter = filter;
|
||||
}
|
||||
|
||||
void
|
||||
RC_Channel::set_type(uint8_t t)
|
||||
{
|
||||
_type = t;
|
||||
//Serial.print("type1: ");
|
||||
//Serial.println(t,DEC);
|
||||
}
|
||||
|
||||
// call after first read
|
||||
|
|
|
@ -98,7 +98,7 @@ class RC_Channel{
|
|||
bool _filter;
|
||||
int8_t _reverse;
|
||||
|
||||
bool _type;
|
||||
uint8_t _type;
|
||||
int16_t _high;
|
||||
int16_t _low;
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue