2020-10-19 23:51:05 -03:00
|
|
|
/*
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
/*
|
|
|
|
support for autotune of multirotors. Based on original autotune code from ArduCopter, written by Leonard Hall
|
|
|
|
Converted to a library by Andrew Tridgell
|
|
|
|
*/
|
|
|
|
|
|
|
|
#pragma once
|
|
|
|
|
2023-12-07 20:03:15 -04:00
|
|
|
#include "AC_AutoTune_config.h"
|
|
|
|
|
|
|
|
#if AC_AUTOTUNE_ENABLED
|
|
|
|
|
2020-10-19 23:51:05 -03:00
|
|
|
#include "AC_AutoTune.h"
|
|
|
|
|
|
|
|
class AC_AutoTune_Multi : public AC_AutoTune
|
|
|
|
{
|
|
|
|
public:
|
|
|
|
// constructor
|
2021-01-17 22:28:20 -04:00
|
|
|
AC_AutoTune_Multi();
|
|
|
|
|
2020-10-19 23:51:05 -03:00
|
|
|
// save gained, called on disarm
|
|
|
|
void save_tuning_gains() override;
|
|
|
|
|
2021-01-18 00:16:08 -04:00
|
|
|
// var_info for holding Parameter information
|
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
|
|
|
|
2020-10-19 23:51:05 -03:00
|
|
|
protected:
|
2021-12-22 10:45:38 -04:00
|
|
|
//
|
|
|
|
// methods to load and save gains
|
|
|
|
//
|
|
|
|
|
|
|
|
// backup original gains and prepare for start of tuning
|
|
|
|
void backup_gains_and_initialise() override;
|
2021-01-17 22:28:20 -04:00
|
|
|
|
2021-12-22 10:45:38 -04:00
|
|
|
// switch to use original gains
|
|
|
|
void load_orig_gains() override;
|
2021-01-17 22:28:20 -04:00
|
|
|
|
2021-12-22 10:45:38 -04:00
|
|
|
// switch to gains found by last successful autotune
|
|
|
|
void load_tuned_gains() override;
|
2021-01-17 22:28:20 -04:00
|
|
|
|
2021-12-22 10:45:38 -04:00
|
|
|
// load gains used between tests. called during testing mode's update-gains step to set gains ahead of return-to-level step
|
|
|
|
void load_intra_test_gains() override;
|
|
|
|
|
|
|
|
// load test gains
|
|
|
|
void load_test_gains() override;
|
2021-01-17 22:28:20 -04:00
|
|
|
|
2023-10-11 04:41:49 -03:00
|
|
|
// reset the test variables for multi
|
2022-01-07 14:37:02 -04:00
|
|
|
void reset_vehicle_test_variables() override {};
|
|
|
|
|
|
|
|
// reset the update gain variables for multi
|
|
|
|
void reset_update_gain_variables() override {};
|
2021-12-22 23:37:31 -04:00
|
|
|
|
2020-10-19 23:51:05 -03:00
|
|
|
void test_init() override;
|
|
|
|
void test_run(AxisType test_axis, const float dir_sign) override;
|
2022-01-07 14:37:02 -04:00
|
|
|
|
2023-10-11 04:41:49 -03:00
|
|
|
// send intermittent updates to user on status of tune
|
2020-10-19 23:51:05 -03:00
|
|
|
void do_gcs_announcements() override;
|
2021-01-17 22:28:20 -04:00
|
|
|
|
2022-01-07 14:37:02 -04:00
|
|
|
// send post test updates to user
|
|
|
|
void do_post_test_gcs_announcements() override {};
|
|
|
|
|
2022-02-04 19:29:54 -04:00
|
|
|
// report final gains for a given axis to GCS
|
|
|
|
void report_final_gains(AxisType test_axis) const override;
|
|
|
|
|
2021-01-17 22:28:20 -04:00
|
|
|
// update gains for the rate P up tune type
|
2020-10-19 23:51:05 -03:00
|
|
|
void updating_rate_p_up_all(AxisType test_axis) override;
|
2021-01-17 22:28:20 -04:00
|
|
|
|
|
|
|
// update gains for the rate D up tune type
|
2020-10-19 23:51:05 -03:00
|
|
|
void updating_rate_d_up_all(AxisType test_axis) override;
|
2021-01-17 22:28:20 -04:00
|
|
|
|
|
|
|
// update gains for the rate D down tune type
|
2020-10-19 23:51:05 -03:00
|
|
|
void updating_rate_d_down_all(AxisType test_axis) override;
|
2021-01-17 22:28:20 -04:00
|
|
|
|
|
|
|
// update gains for the rate ff up tune type
|
2021-12-27 10:44:15 -04:00
|
|
|
void updating_rate_ff_up_all(AxisType test_axis) override {
|
|
|
|
// this should never happen
|
|
|
|
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
|
|
|
|
}
|
2021-01-17 22:28:20 -04:00
|
|
|
|
|
|
|
// update gains for the angle P up tune type
|
2020-10-19 23:51:05 -03:00
|
|
|
void updating_angle_p_up_all(AxisType test_axis) override;
|
2021-01-17 22:28:20 -04:00
|
|
|
|
|
|
|
// update gains for the angle P down tune type
|
2020-10-19 23:51:05 -03:00
|
|
|
void updating_angle_p_down_all(AxisType test_axis) override;
|
2021-01-17 22:28:20 -04:00
|
|
|
|
|
|
|
// update gains for the max gain tune type
|
2021-12-27 10:44:15 -04:00
|
|
|
void updating_max_gains_all(AxisType test_axis) override {
|
|
|
|
// this should never happen
|
|
|
|
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
|
|
|
|
}
|
2020-10-19 23:51:05 -03:00
|
|
|
|
2021-12-27 00:53:50 -04:00
|
|
|
// set gains post tune for the tune type
|
|
|
|
void set_gains_post_tune(AxisType test_axis) override;
|
2021-01-17 22:28:20 -04:00
|
|
|
|
2021-01-18 00:16:08 -04:00
|
|
|
// reverse direction for twitch test
|
|
|
|
bool twitch_reverse_direction() override { return !positive_direction; }
|
|
|
|
|
2020-10-19 23:51:05 -03:00
|
|
|
void Log_AutoTune() override;
|
|
|
|
void Log_AutoTuneDetails() override;
|
2021-12-27 10:44:15 -04:00
|
|
|
void Log_AutoTuneSweep() override {
|
|
|
|
// this should never happen
|
|
|
|
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
|
|
|
|
}
|
2020-10-19 23:51:05 -03:00
|
|
|
void Log_Write_AutoTune(uint8_t axis, uint8_t tune_step, float meas_target, float meas_min, float meas_max, float new_gain_rp, float new_gain_rd, float new_gain_sp, float new_ddt);
|
|
|
|
void Log_Write_AutoTuneDetails(float angle_cd, float rate_cds);
|
|
|
|
|
2021-12-25 23:43:10 -04:00
|
|
|
void set_tune_sequence() override {
|
|
|
|
tune_seq[0] = RD_UP;
|
|
|
|
tune_seq[1] = RD_DOWN;
|
|
|
|
tune_seq[2] = RP_UP;
|
|
|
|
tune_seq[3] = SP_DOWN;
|
|
|
|
tune_seq[4] = SP_UP;
|
|
|
|
tune_seq[5] = TUNE_COMPLETE;
|
|
|
|
}
|
|
|
|
|
2021-12-27 00:53:50 -04:00
|
|
|
// get_axis_bitmask accessor
|
|
|
|
uint8_t get_axis_bitmask() const override { return axis_bitmask; }
|
|
|
|
|
2021-12-28 00:23:19 -04:00
|
|
|
// get_testing_step_timeout_ms accessor
|
|
|
|
uint32_t get_testing_step_timeout_ms() const override;
|
|
|
|
|
2020-10-19 23:51:05 -03:00
|
|
|
private:
|
2021-12-12 09:43:52 -04:00
|
|
|
// twitch test functions for multicopter
|
|
|
|
void twitch_test_init();
|
|
|
|
void twitch_test_run(AxisType test_axis, const float dir_sign);
|
|
|
|
|
|
|
|
void twitching_test_rate(float rate, float rate_target, float &meas_rate_min, float &meas_rate_max);
|
|
|
|
void twitching_abort_rate(float angle, float rate, float angle_max, float meas_rate_min);
|
|
|
|
void twitching_test_angle(float angle, float rate, float angle_target, float &meas_angle_min, float &meas_angle_max, float &meas_rate_min, float &meas_rate_max);
|
|
|
|
|
|
|
|
// measure acceleration during twitch test
|
|
|
|
void twitching_measure_acceleration(float &rate_of_change, float rate_measurement, float &rate_measurement_max) const;
|
|
|
|
|
2020-10-19 23:51:05 -03:00
|
|
|
// updating_rate_d_up - increase D and adjust P to optimize the D term for a little bounce back
|
|
|
|
// optimize D term while keeping the maximum just below the target by adjusting P
|
|
|
|
void updating_rate_d_up(float &tune_d, float tune_d_min, float tune_d_max, float tune_d_step_ratio, float &tune_p, float tune_p_min, float tune_p_max, float tune_p_step_ratio, float rate_target, float meas_rate_min, float meas_rate_max);
|
2021-01-17 22:28:20 -04:00
|
|
|
|
2020-10-19 23:51:05 -03:00
|
|
|
// updating_rate_d_down - decrease D and adjust P to optimize the D term for no bounce back
|
|
|
|
// optimize D term while keeping the maximum just below the target by adjusting P
|
|
|
|
void updating_rate_d_down(float &tune_d, float tune_d_min, float tune_d_step_ratio, float &tune_p, float tune_p_min, float tune_p_max, float tune_p_step_ratio, float rate_target, float meas_rate_min, float meas_rate_max);
|
2021-01-17 22:28:20 -04:00
|
|
|
|
2020-10-19 23:51:05 -03:00
|
|
|
// updating_rate_p_up_d_down - increase P to ensure the target is reached while checking bounce back isn't increasing
|
|
|
|
// P is increased until we achieve our target within a reasonable time while reducing D if bounce back increases above the threshold
|
|
|
|
void updating_rate_p_up_d_down(float &tune_d, float tune_d_min, float tune_d_step_ratio, float &tune_p, float tune_p_min, float tune_p_max, float tune_p_step_ratio, float rate_target, float meas_rate_min, float meas_rate_max);
|
2021-01-17 22:28:20 -04:00
|
|
|
|
2020-10-19 23:51:05 -03:00
|
|
|
// updating_angle_p_down - decrease P until we don't reach the target before time out
|
|
|
|
// P is decreased to ensure we are not overshooting the target
|
|
|
|
void updating_angle_p_down(float &tune_p, float tune_p_min, float tune_p_step_ratio, float angle_target, float meas_angle_max, float meas_rate_min, float meas_rate_max);
|
2021-01-17 22:28:20 -04:00
|
|
|
|
2020-10-19 23:51:05 -03:00
|
|
|
// updating_angle_p_up - increase P to ensure the target is reached
|
|
|
|
// P is increased until we achieve our target within a reasonable time
|
|
|
|
void updating_angle_p_up(float &tune_p, float tune_p_max, float tune_p_step_ratio, float angle_target, float meas_angle_max, float meas_rate_min, float meas_rate_max);
|
2021-01-18 00:16:08 -04:00
|
|
|
|
2023-10-11 04:41:49 -03:00
|
|
|
// report gain formatting helper
|
2022-02-04 19:29:54 -04:00
|
|
|
void report_axis_gains(const char* axis_string, float rate_P, float rate_I, float rate_D, float angle_P, float max_accel) const;
|
|
|
|
|
2021-12-27 00:53:50 -04:00
|
|
|
// parameters
|
|
|
|
AP_Int8 axis_bitmask; // axes to be tuned
|
|
|
|
AP_Float aggressiveness; // aircraft response aggressiveness to be tuned
|
|
|
|
AP_Float min_d; // minimum rate d gain allowed during tuning
|
2020-10-19 23:51:05 -03:00
|
|
|
};
|
2023-12-07 20:03:15 -04:00
|
|
|
|
|
|
|
#endif // AC_AUTOTUNE_ENABLED
|