mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_L1_Control: 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
99499dece2
commit
31092da426
@ -21,12 +21,13 @@
|
||||
|
||||
class AP_L1_Control : public AP_Navigation {
|
||||
public:
|
||||
static AP_L1_Control create(AP_AHRS &ahrs, const AP_SpdHgtControl *spdHgtControl) {
|
||||
return AP_L1_Control{ahrs, spdHgtControl};
|
||||
AP_L1_Control(AP_AHRS &ahrs, const AP_SpdHgtControl *spdHgtControl)
|
||||
: _ahrs(ahrs)
|
||||
, _spdHgtControl(spdHgtControl)
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
}
|
||||
|
||||
constexpr AP_L1_Control(AP_L1_Control &&other) = default;
|
||||
|
||||
/* Do not allow copies */
|
||||
AP_L1_Control(const AP_L1_Control &other) = delete;
|
||||
AP_L1_Control &operator=(const AP_L1_Control&) = delete;
|
||||
@ -75,13 +76,6 @@ public:
|
||||
}
|
||||
|
||||
private:
|
||||
AP_L1_Control(AP_AHRS &ahrs, const AP_SpdHgtControl *spdHgtControl)
|
||||
: _ahrs(ahrs)
|
||||
, _spdHgtControl(spdHgtControl)
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
}
|
||||
|
||||
// reference to the AHRS object
|
||||
AP_AHRS &_ahrs;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user