mirror of https://github.com/ArduPilot/ardupilot
RC_Channel: add and use RC_Channel_config.h
This commit is contained in:
parent
3c3f383601
commit
f81de35cd5
|
@ -17,6 +17,10 @@
|
||||||
* RC_Channel.cpp - class for one RC channel input
|
* RC_Channel.cpp - class for one RC channel input
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
#include "RC_Channel_config.h"
|
||||||
|
|
||||||
|
#if AP_RC_CHANNEL_ENABLED
|
||||||
|
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
#include <cmath>
|
#include <cmath>
|
||||||
|
|
||||||
|
@ -1721,3 +1725,5 @@ void RC_Channels::convert_options(const RC_Channel::aux_func_t old_option, const
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif // AP_RC_CHANNEL_ENABLED
|
||||||
|
|
|
@ -2,15 +2,15 @@
|
||||||
/// @brief RC_Channel manager, with EEPROM-backed storage of constants.
|
/// @brief RC_Channel manager, with EEPROM-backed storage of constants.
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#include "RC_Channel_config.h"
|
||||||
|
|
||||||
|
#if AP_RC_CHANNEL_ENABLED
|
||||||
|
|
||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
#include <AP_Param/AP_Param.h>
|
#include <AP_Param/AP_Param.h>
|
||||||
#include <AP_Math/AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
#include <AP_Common/Bitmask.h>
|
#include <AP_Common/Bitmask.h>
|
||||||
|
|
||||||
#ifndef AP_RC_CHANNEL_AUX_FUNCTION_STRINGS_ENABLED
|
|
||||||
#define AP_RC_CHANNEL_AUX_FUNCTION_STRINGS_ENABLED 1
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#define NUM_RC_CHANNELS 16
|
#define NUM_RC_CHANNELS 16
|
||||||
|
|
||||||
/// @class RC_Channel
|
/// @class RC_Channel
|
||||||
|
@ -680,3 +680,5 @@ private:
|
||||||
};
|
};
|
||||||
|
|
||||||
RC_Channels &rc();
|
RC_Channels &rc();
|
||||||
|
|
||||||
|
#endif // AP_RC_CHANNEL_ENABLED
|
||||||
|
|
|
@ -0,0 +1,11 @@
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <AP_HAL/AP_HAL_Boards.h>
|
||||||
|
|
||||||
|
#ifndef AP_RC_CHANNEL_ENABLED
|
||||||
|
#define AP_RC_CHANNEL_ENABLED 1
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_RC_CHANNEL_AUX_FUNCTION_STRINGS_ENABLED
|
||||||
|
#define AP_RC_CHANNEL_AUX_FUNCTION_STRINGS_ENABLED AP_RC_CHANNEL_ENABLED
|
||||||
|
#endif
|
|
@ -18,6 +18,10 @@
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
#include "RC_Channel_config.h"
|
||||||
|
|
||||||
|
#if AP_RC_CHANNEL_ENABLED
|
||||||
|
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
#include <cmath>
|
#include <cmath>
|
||||||
|
|
||||||
|
@ -307,3 +311,5 @@ RC_Channels &rc()
|
||||||
{
|
{
|
||||||
return *RC_Channels::get_singleton();
|
return *RC_Channels::get_singleton();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif // AP_RC_CHANNEL_ENABLED
|
||||||
|
|
|
@ -1,5 +1,9 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#include "RC_Channel_config.h"
|
||||||
|
|
||||||
|
#if AP_RC_CHANNEL_ENABLED
|
||||||
|
|
||||||
#include "RC_Channel.h"
|
#include "RC_Channel.h"
|
||||||
|
|
||||||
|
|
||||||
|
@ -109,3 +113,5 @@ const AP_Param::GroupInfo RC_Channels::var_info[] = {
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#endif // AP_RC_CHANNEL_ENABLED
|
||||||
|
|
Loading…
Reference in New Issue