mirror of https://github.com/ArduPilot/ardupilot
APM_Control: 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
5f4680bf2c
commit
1dac512567
|
@ -9,13 +9,14 @@
|
|||
|
||||
class AP_PitchController {
|
||||
public:
|
||||
static AP_PitchController create(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms,
|
||||
DataFlash_Class &_dataflash) {
|
||||
return AP_PitchController{ahrs, parms, _dataflash};
|
||||
AP_PitchController(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms, DataFlash_Class &_dataflash)
|
||||
: aparm(parms)
|
||||
, autotune(gains, AP_AutoTune::AUTOTUNE_PITCH, parms, _dataflash)
|
||||
, _ahrs(ahrs)
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
}
|
||||
|
||||
constexpr AP_PitchController(AP_PitchController &&other) = default;
|
||||
|
||||
/* Do not allow copies */
|
||||
AP_PitchController(const AP_PitchController &other) = delete;
|
||||
AP_PitchController &operator=(const AP_PitchController&) = delete;
|
||||
|
@ -38,14 +39,6 @@ public:
|
|||
AP_Float &kFF(void) { return gains.FF; }
|
||||
|
||||
private:
|
||||
AP_PitchController(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms, DataFlash_Class &_dataflash)
|
||||
: aparm(parms)
|
||||
, autotune(gains, AP_AutoTune::AUTOTUNE_PITCH, parms, _dataflash)
|
||||
, _ahrs(ahrs)
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
}
|
||||
|
||||
const AP_Vehicle::FixedWing &aparm;
|
||||
AP_AutoTune::ATGains gains;
|
||||
AP_AutoTune autotune;
|
||||
|
|
|
@ -9,13 +9,14 @@
|
|||
|
||||
class AP_RollController {
|
||||
public:
|
||||
static AP_RollController create(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms,
|
||||
DataFlash_Class &_dataflash) {
|
||||
return AP_RollController{ahrs, parms, _dataflash};
|
||||
AP_RollController(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms, DataFlash_Class &_dataflash)
|
||||
: aparm(parms)
|
||||
, autotune(gains, AP_AutoTune::AUTOTUNE_ROLL, parms, _dataflash)
|
||||
, _ahrs(ahrs)
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
}
|
||||
|
||||
constexpr AP_RollController(AP_RollController &&other) = default;
|
||||
|
||||
/* Do not allow copies */
|
||||
AP_RollController(const AP_RollController &other) = delete;
|
||||
AP_RollController &operator=(const AP_RollController&) = delete;
|
||||
|
@ -45,14 +46,6 @@ public:
|
|||
AP_Float &kFF(void) { return gains.FF; }
|
||||
|
||||
private:
|
||||
AP_RollController(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms, DataFlash_Class &_dataflash)
|
||||
: aparm(parms)
|
||||
, autotune(gains, AP_AutoTune::AUTOTUNE_ROLL, parms, _dataflash)
|
||||
, _ahrs(ahrs)
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
}
|
||||
|
||||
const AP_Vehicle::FixedWing &aparm;
|
||||
AP_AutoTune::ATGains gains;
|
||||
AP_AutoTune autotune;
|
||||
|
|
|
@ -7,12 +7,12 @@
|
|||
|
||||
class AP_SteerController {
|
||||
public:
|
||||
static AP_SteerController create(AP_AHRS &ahrs) {
|
||||
return AP_SteerController{ahrs};
|
||||
AP_SteerController(AP_AHRS &ahrs)
|
||||
: _ahrs(ahrs)
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
}
|
||||
|
||||
constexpr AP_SteerController(AP_SteerController &&other) = default;
|
||||
|
||||
/* Do not allow copies */
|
||||
AP_SteerController(const AP_SteerController &other) = delete;
|
||||
AP_SteerController &operator=(const AP_SteerController&) = delete;
|
||||
|
@ -53,12 +53,6 @@ public:
|
|||
}
|
||||
|
||||
private:
|
||||
AP_SteerController(AP_AHRS &ahrs)
|
||||
: _ahrs(ahrs)
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
}
|
||||
|
||||
AP_Float _tau;
|
||||
AP_Float _K_FF;
|
||||
AP_Float _K_P;
|
||||
|
|
|
@ -8,12 +8,16 @@
|
|||
|
||||
class AP_YawController {
|
||||
public:
|
||||
static AP_YawController create(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms) {
|
||||
return AP_YawController{ahrs, parms};
|
||||
AP_YawController(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms)
|
||||
: aparm(parms)
|
||||
, _ahrs(ahrs)
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
_pid_info.desired = 0;
|
||||
_pid_info.FF = 0;
|
||||
_pid_info.P = 0;
|
||||
}
|
||||
|
||||
constexpr AP_YawController(AP_YawController &&other) = default;
|
||||
|
||||
/* Do not allow copies */
|
||||
AP_YawController(const AP_YawController &other) = delete;
|
||||
AP_YawController &operator=(const AP_YawController&) = delete;
|
||||
|
@ -27,16 +31,6 @@ public:
|
|||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
private:
|
||||
AP_YawController(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms)
|
||||
: aparm(parms)
|
||||
, _ahrs(ahrs)
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
_pid_info.desired = 0;
|
||||
_pid_info.FF = 0;
|
||||
_pid_info.P = 0;
|
||||
}
|
||||
|
||||
const AP_Vehicle::FixedWing &aparm;
|
||||
AP_Float _K_A;
|
||||
AP_Float _K_I;
|
||||
|
|
Loading…
Reference in New Issue