mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_LandingGear: 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
31092da426
commit
ad99b04de7
@ -12,9 +12,10 @@
|
||||
/// @brief Class managing the control of landing gear
|
||||
class AP_LandingGear {
|
||||
public:
|
||||
static AP_LandingGear create() { return AP_LandingGear{}; }
|
||||
|
||||
constexpr AP_LandingGear(AP_LandingGear &&other) = default;
|
||||
AP_LandingGear() {
|
||||
// setup parameter defaults
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
}
|
||||
|
||||
/* Do not allow copies */
|
||||
AP_LandingGear(const AP_LandingGear &other) = delete;
|
||||
@ -46,11 +47,6 @@ public:
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
private:
|
||||
AP_LandingGear() {
|
||||
// setup parameter defaults
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
}
|
||||
|
||||
// Parameters
|
||||
AP_Int16 _servo_retract_pwm; // PWM value to move servo to when gear is retracted
|
||||
AP_Int16 _servo_deploy_pwm; // PWM value to move servo to when gear is deployed
|
||||
|
Loading…
Reference in New Issue
Block a user