Browse Source

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
master
Andrew Tridgell 7 years ago
parent
commit
e9b847b5ee
  1. 6
      libraries/AP_RCMapper/AP_RCMapper.h

6
libraries/AP_RCMapper/AP_RCMapper.h

@ -6,9 +6,7 @@ @@ -6,9 +6,7 @@
class RCMapper {
public:
static RCMapper create() { return RCMapper{}; }
constexpr RCMapper(RCMapper &&other) = default;
RCMapper();
/* Do not allow copies */
RCMapper(const RCMapper &other) = delete;
@ -35,8 +33,6 @@ public: @@ -35,8 +33,6 @@ public:
static const struct AP_Param::GroupInfo var_info[];
private:
RCMapper();
// channel mappings
AP_Int8 _ch_roll;
AP_Int8 _ch_pitch;

Loading…
Cancel
Save