mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AC_Avoidance: 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
9ed3ca3d35
commit
d5c55e0dfe
@ -28,14 +28,7 @@
|
||||
*/
|
||||
class AC_Avoid {
|
||||
public:
|
||||
static AC_Avoid create(const AP_AHRS& ahrs,
|
||||
const AC_Fence& fence,
|
||||
const AP_Proximity& proximity,
|
||||
const AP_Beacon* beacon = nullptr) {
|
||||
return AC_Avoid{ahrs, fence, proximity, beacon};
|
||||
}
|
||||
|
||||
constexpr AC_Avoid(AC_Avoid &&other) = default;
|
||||
AC_Avoid(const AP_AHRS& ahrs, const AC_Fence& fence, const AP_Proximity& proximity, const AP_Beacon* beacon = nullptr);
|
||||
|
||||
/* Do not allow copies */
|
||||
AC_Avoid(const AC_Avoid &other) = delete;
|
||||
@ -64,8 +57,6 @@ public:
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
private:
|
||||
AC_Avoid(const AP_AHRS& ahrs, const AC_Fence& fence, const AP_Proximity& proximity, const AP_Beacon* beacon = nullptr);
|
||||
|
||||
/*
|
||||
* Adjusts the desired velocity for the circular fence.
|
||||
*/
|
||||
|
Loading…
Reference in New Issue
Block a user