mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
Copter: AutoTune remove unused local variable
This commit is contained in:
parent
e8cc5d6312
commit
c1134c1639
@ -900,7 +900,6 @@ void Copter::autotune_load_intra_test_gains()
|
|||||||
// called by autotune_attitude_control() just before it beings testing a gain (i.e. just before it twitches)
|
// called by autotune_attitude_control() just before it beings testing a gain (i.e. just before it twitches)
|
||||||
void Copter::autotune_load_twitch_gains()
|
void Copter::autotune_load_twitch_gains()
|
||||||
{
|
{
|
||||||
bool failed = true;
|
|
||||||
switch (autotune_state.axis) {
|
switch (autotune_state.axis) {
|
||||||
case AUTOTUNE_AXIS_ROLL:
|
case AUTOTUNE_AXIS_ROLL:
|
||||||
g.pid_rate_roll.kP(tune_roll_rp);
|
g.pid_rate_roll.kP(tune_roll_rp);
|
||||||
|
Loading…
Reference in New Issue
Block a user