Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AC_Autotune: only save gains if disarmed in Autotune #10952

Merged
merged 4 commits into from
May 6, 2019
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions ArduCopter/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -499,6 +499,7 @@ class ModeAutoTune : public Mode {

void save_tuning_gains();
void stop();
void reset();

protected:

Expand Down
5 changes: 5 additions & 0 deletions ArduCopter/mode_autotune.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -173,4 +173,9 @@ void Copter::ModeAutoTune::stop()
copter.autotune.stop();
}

void Copter::ModeAutoTune::reset()
{
copter.autotune.reset();
}

#endif // AUTOTUNE_ENABLED == ENABLED
6 changes: 5 additions & 1 deletion ArduCopter/motors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -266,7 +266,11 @@ void Copter::init_disarm_motors()

#if AUTOTUNE_ENABLED == ENABLED
// save auto tuned parameters
mode_autotune.save_tuning_gains();
if (control_mode == AUTOTUNE) {;
mode_autotune.save_tuning_gains();
} else {
mode_autotune.reset();
}
#endif

// we are not in the air
Expand Down
6 changes: 5 additions & 1 deletion ArduPlane/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -502,7 +502,11 @@ bool Plane::disarm_motors(void)

#if QAUTOTUNE_ENABLED
//save qautotune gains if enabled and success
quadplane.qautotune.save_tuning_gains();
if (control_mode == &mode_qautotune) {
quadplane.qautotune.save_tuning_gains();
} else {
quadplane.qautotune.reset();
}
#endif

return true;
Expand Down
20 changes: 14 additions & 6 deletions Tools/autotest/quadplane.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,10 +7,13 @@
from pymavlink import mavutil

from common import AutoTest
from common import AutoTestTimeoutException

from pysim import util
from pysim import vehicleinfo
import operator


# get location of scripts
testdir = os.path.dirname(os.path.realpath(__file__))
SITL_START_LOCATION = mavutil.location(-27.274439, 151.290064, 343, 8.7)
Expand Down Expand Up @@ -133,12 +136,17 @@ def fly_qautotune(self):
continue
self.progress("STATUSTEXT (%u<%u): %s" % (now, deadline, m.text))
if "AutoTune: Success" in m.text:
self.progress("AUTOTUNE OK (%u seconds)" % (now - tstart))
# near enough for now:
self.change_mode("QLAND")
self.mavproxy.expect("AutoTune: Saved gains for Roll Pitch Yaw")
self.mav.motors_disarmed_wait()
return
break
self.progress("AUTOTUNE OK (%u seconds)" % (now - tstart))
self.set_rc(3, 1200)
self.wait_altitude(-5, 1, relative=True, timeout=30)
while self.get_sim_time_cached() < deadline:
self.mavproxy.send('disarm\n')
try:
self.wait_text("AutoTune: Saved gains for Roll Pitch Yaw", timeout=0.5)
except AutoTestTimeoutException as e:
continue
break
self.mav.motors_disarmed_wait()

def test_pid_tuning(self):
Expand Down
4 changes: 1 addition & 3 deletions libraries/AC_AutoTune/AC_AutoTune.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1215,9 +1215,7 @@ void AC_AutoTune::save_tuning_gains()
update_gcs(AUTOTUNE_MESSAGE_SAVED_GAINS);
Log_Write_Event(EVENT_AUTOTUNE_SAVEDGAINS);

// reset Autotune so that gains are not saved again and autotune can be run again.
mode = UNINITIALISED;
axes_completed = 0;
reset();
}

// update_gcs - send message to ground station
Expand Down
6 changes: 6 additions & 0 deletions libraries/AC_AutoTune/AC_AutoTune.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,12 @@ class AC_AutoTune {
// stop tune, reverting gains
void stop();

// reset Autotune so that gains are not saved again and autotune can be run again.
void reset() {
mode = UNINITIALISED;
axes_completed = 0;
}

// var_info for holding Parameter information
static const struct AP_Param::GroupInfo var_info[];

Expand Down