mirror of https://github.com/ArduPilot/ardupilot
AP_RCMapper: add static create method
This commit is contained in:
parent
72fd2d6f05
commit
c10a91964f
|
@ -4,12 +4,15 @@
|
|||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
|
||||
class RCMapper
|
||||
{
|
||||
class RCMapper {
|
||||
public:
|
||||
/// Constructor
|
||||
///
|
||||
RCMapper();
|
||||
static RCMapper create() { return RCMapper{}; }
|
||||
|
||||
constexpr RCMapper(RCMapper &&other) = default;
|
||||
|
||||
/* Do not allow copies */
|
||||
RCMapper(const RCMapper &other) = delete;
|
||||
RCMapper &operator=(const RCMapper&) = delete;
|
||||
|
||||
/// roll - return input channel number for roll / aileron input
|
||||
uint8_t roll() const { return _ch_roll; }
|
||||
|
@ -32,6 +35,8 @@ public:
|
|||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
private:
|
||||
RCMapper();
|
||||
|
||||
// channel mappings
|
||||
AP_Int8 _ch_roll;
|
||||
AP_Int8 _ch_pitch;
|
||||
|
|
Loading…
Reference in New Issue