AP_Parachute: 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:
Andrew Tridgell 2017-12-13 12:06:13 +11:00
parent 0d4dca0394
commit e798b38271
2 changed files with 12 additions and 18 deletions

View File

@ -25,12 +25,18 @@
class AP_Parachute {
public:
static AP_Parachute create(AP_Relay &relay) {
return AP_Parachute{relay};
/// Constructor
AP_Parachute(AP_Relay &relay)
: _relay(relay)
, _release_time(0)
, _release_initiated(false)
, _release_in_progress(false)
, _released(false)
{
// setup parameter defaults
AP_Param::setup_object_defaults(this, var_info);
}
constexpr AP_Parachute(AP_Parachute &&other) = default;
/* Do not allow copies */
AP_Parachute(const AP_Parachute &other) = delete;
AP_Parachute &operator=(const AP_Parachute&) = delete;
@ -63,18 +69,6 @@ public:
static const struct AP_Param::GroupInfo var_info[];
private:
/// Constructor
AP_Parachute(AP_Relay &relay)
: _relay(relay)
, _release_time(0)
, _release_initiated(false)
, _release_in_progress(false)
, _released(false)
{
// setup parameter defaults
AP_Param::setup_object_defaults(this, var_info);
}
// Parameters
AP_Int8 _enabled; // 1 if parachute release is enabled
AP_Int8 _release_type; // 0:Servo,1:Relay

View File

@ -19,10 +19,10 @@ void loop();
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
// Relay
static AP_Relay relay = AP_Relay::create();
static AP_Relay relay;
// Parachute
static AP_Parachute parachute = AP_Parachute::create(relay);
static AP_Parachute parachute{relay};
void setup()
{