From e9b847b5ee8317dc5b6599c7e57e49c57afc8b56 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 13 Dec 2017 12:06:13 +1100 Subject: [PATCH] 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 --- libraries/AP_RCMapper/AP_RCMapper.h | 6 +----- 1 file changed, 1 insertion(+), 5 deletions(-) diff --git a/libraries/AP_RCMapper/AP_RCMapper.h b/libraries/AP_RCMapper/AP_RCMapper.h index 22fe89af05..88da33bb52 100644 --- a/libraries/AP_RCMapper/AP_RCMapper.h +++ b/libraries/AP_RCMapper/AP_RCMapper.h @@ -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: static const struct AP_Param::GroupInfo var_info[]; private: - RCMapper(); - // channel mappings AP_Int8 _ch_roll; AP_Int8 _ch_pitch;