mirror of https://github.com/ArduPilot/ardupilot
APM_Control: added tuning accessors
This commit is contained in:
parent
27fb35253c
commit
8586b0ae5a
|
@ -30,6 +30,12 @@ public:
|
||||||
|
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
|
// tuning accessors
|
||||||
|
void kP(float v) { gains.P.set(v); }
|
||||||
|
void kI(float v) { gains.I.set(v); }
|
||||||
|
void kD(float v) { gains.D.set(v); }
|
||||||
|
void kFF(float v) { gains.FF.set(v); }
|
||||||
|
|
||||||
private:
|
private:
|
||||||
const AP_Vehicle::FixedWing &aparm;
|
const AP_Vehicle::FixedWing &aparm;
|
||||||
AP_AutoTune::ATGains gains;
|
AP_AutoTune::ATGains gains;
|
||||||
|
|
|
@ -30,6 +30,13 @@ public:
|
||||||
|
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
|
|
||||||
|
// tuning accessors
|
||||||
|
void kP(float v) { gains.P.set(v); }
|
||||||
|
void kI(float v) { gains.I.set(v); }
|
||||||
|
void kD(float v) { gains.D.set(v); }
|
||||||
|
void kFF(float v) { gains.FF.set(v); }
|
||||||
|
|
||||||
private:
|
private:
|
||||||
const AP_Vehicle::FixedWing &aparm;
|
const AP_Vehicle::FixedWing &aparm;
|
||||||
AP_AutoTune::ATGains gains;
|
AP_AutoTune::ATGains gains;
|
||||||
|
|
Loading…
Reference in New Issue