mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-11 10:23:59 -04:00
APM_Control: add static create method
This commit is contained in:
parent
05c870a4d4
commit
15527d762f
@ -9,13 +9,16 @@
|
|||||||
|
|
||||||
class AP_PitchController {
|
class AP_PitchController {
|
||||||
public:
|
public:
|
||||||
AP_PitchController(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms, DataFlash_Class &_dataflash) :
|
static AP_PitchController create(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms,
|
||||||
aparm(parms),
|
DataFlash_Class &_dataflash) {
|
||||||
autotune(gains, AP_AutoTune::AUTOTUNE_PITCH, parms, _dataflash),
|
return AP_PitchController{ahrs, 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;
|
||||||
|
|
||||||
int32_t get_rate_out(float desired_rate, float scaler);
|
int32_t get_rate_out(float desired_rate, float scaler);
|
||||||
int32_t get_servo_out(int32_t angle_err, float scaler, bool disable_integrator);
|
int32_t get_servo_out(int32_t angle_err, float scaler, bool disable_integrator);
|
||||||
@ -35,7 +38,15 @@ public:
|
|||||||
AP_Float &kFF(void) { return gains.FF; }
|
AP_Float &kFF(void) { return gains.FF; }
|
||||||
|
|
||||||
private:
|
private:
|
||||||
const AP_Vehicle::FixedWing &aparm;
|
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::ATGains gains;
|
||||||
AP_AutoTune autotune;
|
AP_AutoTune autotune;
|
||||||
AP_Int16 _max_rate_neg;
|
AP_Int16 _max_rate_neg;
|
||||||
|
@ -9,13 +9,16 @@
|
|||||||
|
|
||||||
class AP_RollController {
|
class AP_RollController {
|
||||||
public:
|
public:
|
||||||
AP_RollController(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms, DataFlash_Class &_dataflash) :
|
static AP_RollController create(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms,
|
||||||
aparm(parms),
|
DataFlash_Class &_dataflash) {
|
||||||
autotune(gains, AP_AutoTune::AUTOTUNE_ROLL, parms, _dataflash),
|
return AP_RollController{ahrs, 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;
|
||||||
|
|
||||||
int32_t get_rate_out(float desired_rate, float scaler);
|
int32_t get_rate_out(float desired_rate, float scaler);
|
||||||
int32_t get_servo_out(int32_t angle_err, float scaler, bool disable_integrator);
|
int32_t get_servo_out(int32_t angle_err, float scaler, bool disable_integrator);
|
||||||
@ -42,7 +45,15 @@ public:
|
|||||||
AP_Float &kFF(void) { return gains.FF; }
|
AP_Float &kFF(void) { return gains.FF; }
|
||||||
|
|
||||||
private:
|
private:
|
||||||
const AP_Vehicle::FixedWing &aparm;
|
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::ATGains gains;
|
||||||
AP_AutoTune autotune;
|
AP_AutoTune autotune;
|
||||||
uint32_t _last_t;
|
uint32_t _last_t;
|
||||||
|
@ -7,11 +7,15 @@
|
|||||||
|
|
||||||
class AP_SteerController {
|
class AP_SteerController {
|
||||||
public:
|
public:
|
||||||
AP_SteerController(AP_AHRS &ahrs) :
|
static AP_SteerController create(AP_AHRS &ahrs) {
|
||||||
_ahrs(ahrs)
|
return AP_SteerController{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;
|
||||||
|
|
||||||
/*
|
/*
|
||||||
return a steering servo output from -4500 to 4500 given a
|
return a steering servo output from -4500 to 4500 given a
|
||||||
@ -49,7 +53,13 @@ public:
|
|||||||
}
|
}
|
||||||
|
|
||||||
private:
|
private:
|
||||||
AP_Float _tau;
|
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_FF;
|
||||||
AP_Float _K_P;
|
AP_Float _K_P;
|
||||||
AP_Float _K_I;
|
AP_Float _K_I;
|
||||||
|
@ -8,15 +8,15 @@
|
|||||||
|
|
||||||
class AP_YawController {
|
class AP_YawController {
|
||||||
public:
|
public:
|
||||||
AP_YawController(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms) :
|
static AP_YawController create(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms) {
|
||||||
aparm(parms),
|
return AP_YawController{ahrs, parms};
|
||||||
_ahrs(ahrs)
|
}
|
||||||
{
|
|
||||||
AP_Param::setup_object_defaults(this, var_info);
|
constexpr AP_YawController(AP_YawController &&other) = default;
|
||||||
_pid_info.desired = 0;
|
|
||||||
_pid_info.FF = 0;
|
/* Do not allow copies */
|
||||||
_pid_info.P = 0;
|
AP_YawController(const AP_YawController &other) = delete;
|
||||||
}
|
AP_YawController &operator=(const AP_YawController&) = delete;
|
||||||
|
|
||||||
int32_t get_servo_out(float scaler, bool disable_integrator);
|
int32_t get_servo_out(float scaler, bool disable_integrator);
|
||||||
|
|
||||||
@ -27,7 +27,17 @@ public:
|
|||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
private:
|
private:
|
||||||
const AP_Vehicle::FixedWing &aparm;
|
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_A;
|
||||||
AP_Float _K_I;
|
AP_Float _K_I;
|
||||||
AP_Float _K_D;
|
AP_Float _K_D;
|
||||||
|
Loading…
Reference in New Issue
Block a user