AP_TECS: 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:14 +11:00
parent 003851a5c1
commit b6ecce8329
1 changed files with 7 additions and 15 deletions

View File

@ -29,14 +29,15 @@
class AP_TECS : public AP_SpdHgtControl {
public:
static AP_TECS create(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms,
const AP_Landing &landing,
const SoaringController &soaring_controller) {
return AP_TECS{ahrs, parms, landing, soaring_controller};
AP_TECS(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms, const AP_Landing &landing, const SoaringController &soaring_controller)
: _ahrs(ahrs)
, aparm(parms)
, _landing(landing)
, _soaring_controller(soaring_controller)
{
AP_Param::setup_object_defaults(this, var_info);
}
constexpr AP_TECS(AP_TECS &&other) = default;
/* Do not allow copies */
AP_TECS(const AP_TECS &other) = delete;
AP_TECS &operator=(const AP_TECS&) = delete;
@ -122,15 +123,6 @@ public:
static const struct AP_Param::GroupInfo var_info[];
private:
AP_TECS(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms, const AP_Landing &landing, const SoaringController &soaring_controller)
: _ahrs(ahrs)
, aparm(parms)
, _landing(landing)
, _soaring_controller(soaring_controller)
{
AP_Param::setup_object_defaults(this, var_info);
}
// Last time update_50Hz was called
uint64_t _update_50hz_last_usec;