From 1c503ee4594540ab233911e20ac8713d78a551bc Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 13 Dec 2017 12:06:15 +1100 Subject: [PATCH] SRV_Channel: 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/SRV_Channel/SRV_Channel.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/SRV_Channel/SRV_Channel.h b/libraries/SRV_Channel/SRV_Channel.h index bc57b901d5..692dfc2126 100644 --- a/libraries/SRV_Channel/SRV_Channel.h +++ b/libraries/SRV_Channel/SRV_Channel.h @@ -438,11 +438,11 @@ private: static SRV_Channels *instance; // support for Volz protocol - AP_Volz_Protocol volz = AP_Volz_Protocol::create(); + AP_Volz_Protocol volz; static AP_Volz_Protocol *volz_ptr; // support for SBUS protocol - AP_SBusOut sbus = AP_SBusOut::create(); + AP_SBusOut sbus; static AP_SBusOut *sbus_ptr; SRV_Channel obj_channels[NUM_SERVO_CHANNELS];