AC_Fence: 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
d5c55e0dfe
commit
25b9a7e711
@ -34,11 +34,7 @@
|
||||
class AC_Fence
|
||||
{
|
||||
public:
|
||||
static AC_Fence create(const AP_AHRS_NavEKF &ahrs) {
|
||||
return AC_Fence{ahrs};
|
||||
}
|
||||
|
||||
constexpr AC_Fence(AC_Fence &&other) = default;
|
||||
AC_Fence(const AP_AHRS_NavEKF &ahrs);
|
||||
|
||||
/* Do not allow copies */
|
||||
AC_Fence(const AC_Fence &other) = delete;
|
||||
@ -127,8 +123,6 @@ public:
|
||||
bool geofence_failed() const;
|
||||
|
||||
private:
|
||||
AC_Fence(const AP_AHRS_NavEKF &ahrs);
|
||||
|
||||
/// check_fence_alt_max - true if alt fence has been newly breached
|
||||
bool check_fence_alt_max(float curr_alt);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user