mirror of https://github.com/ArduPilot/ardupilot
AP_RCMapper: removed create() method for objects
See discussion here: https://github.com/ArduPilot/ardupilot/issues/7331 we were getting some uninitialised variables. While it only showed up in AP_SbusOut, it means we can't be sure it won't happen on other objects, so safest to remove the approach Thanks to assistance from Lucas, Peter and Francisco
This commit is contained in:
parent
ffced7d591
commit
e9b847b5ee
|
@ -6,9 +6,7 @@
|
||||||
|
|
||||||
class RCMapper {
|
class RCMapper {
|
||||||
public:
|
public:
|
||||||
static RCMapper create() { return RCMapper{}; }
|
RCMapper();
|
||||||
|
|
||||||
constexpr RCMapper(RCMapper &&other) = default;
|
|
||||||
|
|
||||||
/* Do not allow copies */
|
/* Do not allow copies */
|
||||||
RCMapper(const RCMapper &other) = delete;
|
RCMapper(const RCMapper &other) = delete;
|
||||||
|
@ -35,8 +33,6 @@ public:
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
private:
|
private:
|
||||||
RCMapper();
|
|
||||||
|
|
||||||
// channel mappings
|
// channel mappings
|
||||||
AP_Int8 _ch_roll;
|
AP_Int8 _ch_roll;
|
||||||
AP_Int8 _ch_pitch;
|
AP_Int8 _ch_pitch;
|
||||||
|
|
Loading…
Reference in New Issue