mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 00:13:59 -04:00
Sub: Disable autotune parameters
This commit is contained in:
parent
9c5b304626
commit
4cb9ee947b
@ -1009,6 +1009,7 @@ const AP_Param::Info Sub::var_info[] = {
|
||||
// @Path: ../libraries/AP_RPM/AP_RPM.cpp
|
||||
GOBJECT(rpm_sensor, "RPM", AP_RPM),
|
||||
|
||||
#if AUTOTUNE_ENABLED == ENABLED
|
||||
// @Param: AUTOTUNE_AXES
|
||||
// @DisplayName: Autotune axis bitmask
|
||||
// @Description: 1-byte bitmap of axes to autotune
|
||||
@ -1030,6 +1031,7 @@ const AP_Param::Info Sub::var_info[] = {
|
||||
// @Range: 0.001 0.006
|
||||
// @User: Standard
|
||||
GSCALAR(autotune_min_d, "AUTOTUNE_MIN_D", 0.001f),
|
||||
#endif
|
||||
|
||||
// @Group: NTF_
|
||||
// @Path: ../libraries/AP_Notify/AP_Notify.cpp
|
||||
|
@ -456,9 +456,11 @@ public:
|
||||
|
||||
|
||||
// Autotune
|
||||
#if AUTOTUNE_ENABLED == ENABLED
|
||||
AP_Int8 autotune_axis_bitmask;
|
||||
AP_Float autotune_aggressiveness;
|
||||
AP_Float autotune_min_d;
|
||||
#endif
|
||||
|
||||
AP_Float surface_depth;
|
||||
|
||||
|
@ -565,8 +565,10 @@ private:
|
||||
void gcs_check_input(void);
|
||||
void gcs_send_text(MAV_SEVERITY severity, const char *str);
|
||||
void do_erase_logs(void);
|
||||
#if AUTOTUNE_ENABLED == ENABLED
|
||||
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);
|
||||
#endif
|
||||
void Log_Write_Current();
|
||||
void Log_Write_Optflow();
|
||||
void Log_Write_Nav_Tuning();
|
||||
@ -645,6 +647,7 @@ private:
|
||||
void set_auto_yaw_look_at_heading(float angle_deg, float turn_rate_dps, int8_t direction, uint8_t relative_angle);
|
||||
void set_auto_yaw_roi(const Location &roi_location);
|
||||
float get_auto_heading(void);
|
||||
#if AUTOTUNE_ENABLED == ENABLED
|
||||
bool autotune_init(bool ignore_checks);
|
||||
void autotune_stop();
|
||||
bool autotune_start(bool ignore_checks);
|
||||
@ -667,6 +670,7 @@ private:
|
||||
void autotune_updating_p_up(float &tune_p, float tune_p_max, float tune_p_step_ratio, float target, float measurement_max);
|
||||
void autotune_updating_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 target, float measurement_min, float measurement_max);
|
||||
void autotune_twitching_measure_acceleration(float &rate_of_change, float rate_measurement, float &rate_measurement_max);
|
||||
#endif
|
||||
bool circle_init(bool ignore_checks);
|
||||
void circle_run();
|
||||
bool guided_init(bool ignore_checks);
|
||||
|
Loading…
Reference in New Issue
Block a user