mirror of https://github.com/ArduPilot/ardupilot
Sub: Remove unsupported autotune
This commit is contained in:
parent
dacdd542b7
commit
ca38a344f8
|
@ -6,7 +6,6 @@
|
|||
// uncomment the lines below to disable features (flash sizes listed are for APM2 boards and will underestimate savings on Pixhawk and other boards)
|
||||
//#define LOGGING_ENABLED DISABLED // disable dataflash logging to save 11K of flash space
|
||||
//#define MOUNT DISABLED // disable the camera gimbal to save 8K of flash space
|
||||
#define AUTOTUNE_ENABLED DISABLED // disable the auto tune functionality to save 7k of flash
|
||||
//#define AC_FENCE DISABLED // disable fence to save 2k of flash
|
||||
//#define CAMERA DISABLED // disable camera trigger to save 1k of flash
|
||||
//#define RANGEFINDER_ENABLED DISABLED // disable rangefinder to save 1k of flash
|
||||
|
|
|
@ -157,60 +157,6 @@ void Sub::do_erase_logs(void)
|
|||
gcs_send_text(MAV_SEVERITY_INFO, "Log erase complete");
|
||||
}
|
||||
|
||||
#if AUTOTUNE_ENABLED == ENABLED
|
||||
struct PACKED log_AutoTune {
|
||||
LOG_PACKET_HEADER;
|
||||
uint64_t time_us;
|
||||
uint8_t axis; // roll or pitch
|
||||
uint8_t tune_step; // tuning PI or D up or down
|
||||
float meas_target; // target achieved rotation rate
|
||||
float meas_min; // maximum achieved rotation rate
|
||||
float meas_max; // maximum achieved rotation rate
|
||||
float new_gain_rp; // newly calculated gain
|
||||
float new_gain_rd; // newly calculated gain
|
||||
float new_gain_sp; // newly calculated gain
|
||||
float new_ddt; // newly calculated gain
|
||||
};
|
||||
|
||||
// Write an Autotune data packet
|
||||
void Sub::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)
|
||||
{
|
||||
struct log_AutoTune pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_AUTOTUNE_MSG),
|
||||
time_us : AP_HAL::micros64(),
|
||||
axis : axis,
|
||||
tune_step : tune_step,
|
||||
meas_target : meas_target,
|
||||
meas_min : meas_min,
|
||||
meas_max : meas_max,
|
||||
new_gain_rp : new_gain_rp,
|
||||
new_gain_rd : new_gain_rd,
|
||||
new_gain_sp : new_gain_sp,
|
||||
new_ddt : new_ddt
|
||||
};
|
||||
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
||||
struct PACKED log_AutoTuneDetails {
|
||||
LOG_PACKET_HEADER;
|
||||
uint64_t time_us;
|
||||
float angle_cd; // lean angle in centi-degrees
|
||||
float rate_cds; // current rotation rate in centi-degrees / second
|
||||
};
|
||||
|
||||
// Write an Autotune data packet
|
||||
void Sub::Log_Write_AutoTuneDetails(float angle_cd, float rate_cds)
|
||||
{
|
||||
struct log_AutoTuneDetails pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_AUTOTUNEDETAILS_MSG),
|
||||
time_us : AP_HAL::micros64(),
|
||||
angle_cd : angle_cd,
|
||||
rate_cds : rate_cds
|
||||
};
|
||||
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
#endif
|
||||
|
||||
// Write a Current data packet
|
||||
void Sub::Log_Write_Current()
|
||||
{
|
||||
|
@ -657,12 +603,6 @@ void Sub::Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target
|
|||
|
||||
const struct LogStructure Sub::log_structure[] = {
|
||||
LOG_COMMON_STRUCTURES,
|
||||
#if AUTOTUNE_ENABLED == ENABLED
|
||||
{ LOG_AUTOTUNE_MSG, sizeof(log_AutoTune),
|
||||
"ATUN", "QBBfffffff", "TimeUS,Axis,TuneStep,Targ,Min,Max,RP,RD,SP,ddt" },
|
||||
{ LOG_AUTOTUNEDETAILS_MSG, sizeof(log_AutoTuneDetails),
|
||||
"ATDE", "Qff", "TimeUS,Angle,Rate" },
|
||||
#endif
|
||||
{ LOG_PARAMTUNE_MSG, sizeof(log_ParameterTuning),
|
||||
"PTUN", "QBfHHH", "TimeUS,Param,TunVal,CtrlIn,TunLo,TunHi" },
|
||||
{ LOG_OPTFLOW_MSG, sizeof(log_Optflow),
|
||||
|
@ -761,10 +701,6 @@ void Sub::Log_Read(uint16_t log_num, uint16_t start_page, uint16_t end_page) {}
|
|||
#endif // CLI_ENABLED == ENABLED
|
||||
|
||||
void Sub::do_erase_logs(void) {}
|
||||
void Sub::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 Sub::Log_Write_AutoTuneDetails(float angle_cd, float rate_cds) {}
|
||||
void Sub::Log_Write_Current() {}
|
||||
void Sub::Log_Write_Nav_Tuning() {}
|
||||
void Sub::Log_Write_Control_Tuning() {}
|
||||
|
|
|
@ -313,42 +313,42 @@ const AP_Param::Info Sub::var_info[] = {
|
|||
// @Param: CH7_OPT
|
||||
// @DisplayName: Channel 7 option
|
||||
// @Description: Select which function if performed when CH7 is above 1800 pwm
|
||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost vehicle Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw
|
||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost vehicle Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw
|
||||
// @User: Standard
|
||||
GSCALAR(ch7_option, "CH7_OPT", AUXSW_DO_NOTHING),
|
||||
|
||||
// @Param: CH8_OPT
|
||||
// @DisplayName: Channel 8 option
|
||||
// @Description: Select which function if performed when CH8 is above 1800 pwm
|
||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost vehicle Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw
|
||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost vehicle Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw
|
||||
// @User: Standard
|
||||
GSCALAR(ch8_option, "CH8_OPT", AUXSW_DO_NOTHING),
|
||||
|
||||
// @Param: CH9_OPT
|
||||
// @DisplayName: Channel 9 option
|
||||
// @Description: Select which function if performed when CH9 is above 1800 pwm
|
||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost vehicle Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw
|
||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost vehicle Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw
|
||||
// @User: Standard
|
||||
GSCALAR(ch9_option, "CH9_OPT", AUXSW_DO_NOTHING),
|
||||
|
||||
// @Param: CH10_OPT
|
||||
// @DisplayName: Channel 10 option
|
||||
// @Description: Select which function if performed when CH10 is above 1800 pwm
|
||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost vehicle Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw
|
||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost vehicle Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw
|
||||
// @User: Standard
|
||||
GSCALAR(ch10_option, "CH10_OPT", AUXSW_DO_NOTHING),
|
||||
|
||||
// @Param: CH11_OPT
|
||||
// @DisplayName: Channel 11 option
|
||||
// @Description: Select which function if performed when CH11 is above 1800 pwm
|
||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost vehicle Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw
|
||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost vehicle Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw
|
||||
// @User: Standard
|
||||
GSCALAR(ch11_option, "CH11_OPT", AUXSW_DO_NOTHING),
|
||||
|
||||
// @Param: CH12_OPT
|
||||
// @DisplayName: Channel 12 option
|
||||
// @Description: Select which function if performed when CH12 is above 1800 pwm
|
||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost vehicle Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw
|
||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost vehicle Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw
|
||||
// @User: Standard
|
||||
GSCALAR(ch12_option, "CH12_OPT", AUXSW_DO_NOTHING),
|
||||
#endif
|
||||
|
@ -832,30 +832,6 @@ const AP_Param::Info Sub::var_info[] = {
|
|||
GOBJECT(rpm_sensor, "RPM", AP_RPM),
|
||||
#endif
|
||||
|
||||
#if AUTOTUNE_ENABLED == ENABLED
|
||||
// @Param: AUTOTUNE_AXES
|
||||
// @DisplayName: Autotune axis bitmask
|
||||
// @Description: 1-byte bitmap of axes to autotune
|
||||
// @Values: 7:All,1:Roll Only,2:Pitch Only,4:Yaw Only,3:Roll and Pitch,5:Roll and Yaw,6:Pitch and Yaw
|
||||
// @Bitmask: 0:Roll,1:Pitch,2:Yaw
|
||||
// @User: Standard
|
||||
GSCALAR(autotune_axis_bitmask, "AUTOTUNE_AXES", 7), // AUTOTUNE_AXIS_BITMASK_DEFAULT
|
||||
|
||||
// @Param: AUTOTUNE_AGGR
|
||||
// @DisplayName: Autotune aggressiveness
|
||||
// @Description: Autotune aggressiveness. Defines the bounce back used to detect size of the D term.
|
||||
// @Range: 0.05 0.10
|
||||
// @User: Standard
|
||||
GSCALAR(autotune_aggressiveness, "AUTOTUNE_AGGR", 0.1f),
|
||||
|
||||
// @Param: AUTOTUNE_MIN_D
|
||||
// @DisplayName: AutoTune minimum D
|
||||
// @Description: Defines the minimum D gain
|
||||
// @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
|
||||
GOBJECT(notify, "NTF_", AP_Notify),
|
||||
|
|
|
@ -236,10 +236,6 @@ public:
|
|||
k_param_radio_tuning_high, // Disabled
|
||||
k_param_radio_tuning_low, // Disabled
|
||||
|
||||
// Autotune parameters
|
||||
k_param_autotune_axis_bitmask, // Disabled
|
||||
k_param_autotune_aggressiveness, // Disabled
|
||||
k_param_autotune_min_d, // Disabled
|
||||
};
|
||||
|
||||
AP_Int16 format_version;
|
||||
|
@ -367,13 +363,6 @@ public:
|
|||
AC_P p_pos_xy;
|
||||
AC_P p_alt_hold;
|
||||
|
||||
// Autotune
|
||||
#if AUTOTUNE_ENABLED == ENABLED
|
||||
AP_Int8 autotune_axis_bitmask;
|
||||
AP_Float autotune_aggressiveness;
|
||||
AP_Float autotune_min_d;
|
||||
#endif
|
||||
|
||||
AP_Float surface_depth;
|
||||
AP_Int8 frame_configuration;
|
||||
|
||||
|
|
|
@ -547,10 +547,6 @@ 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();
|
||||
|
@ -624,30 +620,6 @@ 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);
|
||||
void autotune_run();
|
||||
void autotune_attitude_control();
|
||||
void autotune_backup_gains_and_initialise();
|
||||
void autotune_load_orig_gains();
|
||||
void autotune_load_tuned_gains();
|
||||
void autotune_load_intra_test_gains();
|
||||
void autotune_load_twitch_gains();
|
||||
void autotune_save_tuning_gains();
|
||||
void autotune_update_gcs(uint8_t message_id);
|
||||
bool autotune_roll_enabled();
|
||||
bool autotune_pitch_enabled();
|
||||
bool autotune_yaw_enabled();
|
||||
void autotune_twitching_test(float measurement, float target, float &measurement_min, float &measurement_max);
|
||||
void autotune_updating_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 target, float measurement_min, float measurement_max);
|
||||
void autotune_updating_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_updating_p_down(float &tune_p, float tune_p_min, float tune_p_step_ratio, float target, float measurement_max);
|
||||
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);
|
||||
|
|
|
@ -263,12 +263,6 @@
|
|||
# define OPTFLOW DISABLED
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Auto Tuning
|
||||
#ifndef AUTOTUNE_ENABLED
|
||||
# define AUTOTUNE_ENABLED ENABLED
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// gripper
|
||||
#ifndef GRIPPER_ENABLED
|
||||
|
|
File diff suppressed because it is too large
Load Diff
|
@ -57,7 +57,6 @@ enum aux_sw_func {
|
|||
// AUXSW_SPRAYER = 15, // enable/disable the crop sprayer
|
||||
|
||||
AUXSW_AUTO = 16, // change to auto flight mode
|
||||
AUXSW_AUTOTUNE = 17, // auto tune
|
||||
AUXSW_LAND = 18, // change to LAND flight mode
|
||||
AUXSW_GRIPPER = 19, // Operate cargo grippers low=off, middle=neutral, high=on
|
||||
|
||||
|
@ -100,7 +99,6 @@ enum control_mode_t {
|
|||
CIRCLE = 7, // not implemented in sub // automatic circular flight with automatic throttle
|
||||
SURFACE = 9, // automatically return to surface, pilot maintains horizontal control
|
||||
OF_LOITER = 10, // deprecated
|
||||
AUTOTUNE = 15, // not implemented in sub // automatically tune the vehicle's roll and pitch gains
|
||||
POSHOLD = 16, // automatic position hold with manual override, with automatic throttle
|
||||
MANUAL = 19 // Pass-through input with no stabilization
|
||||
};
|
||||
|
@ -252,8 +250,6 @@ enum LoiterModeState {
|
|||
#define LOG_DATA_INT32_MSG 0x16
|
||||
#define LOG_DATA_UINT32_MSG 0x17
|
||||
#define LOG_DATA_FLOAT_MSG 0x18
|
||||
#define LOG_AUTOTUNE_MSG 0x19
|
||||
#define LOG_AUTOTUNEDETAILS_MSG 0x1A
|
||||
#define LOG_MOTBATT_MSG 0x1E
|
||||
#define LOG_PARAMTUNE_MSG 0x1F
|
||||
#define LOG_HELI_MSG 0x20
|
||||
|
@ -299,14 +295,6 @@ enum LoiterModeState {
|
|||
#define DATA_SET_SIMPLE_ON 26
|
||||
#define DATA_SET_SIMPLE_OFF 27
|
||||
#define DATA_SET_SUPERSIMPLE_ON 29
|
||||
#define DATA_AUTOTUNE_INITIALISED 30
|
||||
#define DATA_AUTOTUNE_OFF 31
|
||||
#define DATA_AUTOTUNE_RESTART 32
|
||||
#define DATA_AUTOTUNE_SUCCESS 33
|
||||
#define DATA_AUTOTUNE_FAILED 34
|
||||
#define DATA_AUTOTUNE_REACHED_LIMIT 35
|
||||
#define DATA_AUTOTUNE_PILOT_TESTING 36
|
||||
#define DATA_AUTOTUNE_SAVEDGAINS 37
|
||||
#define DATA_SAVE_TRIM 38
|
||||
#define DATA_SAVEWP_ADD_WP 39
|
||||
#define DATA_FENCE_ENABLE 41
|
||||
|
@ -351,8 +339,7 @@ enum LoiterModeState {
|
|||
#define ERROR_SUBSYSTEM_FLIGHT_MODE 10
|
||||
#define ERROR_SUBSYSTEM_GPS 11 // not used
|
||||
#define ERROR_SUBSYSTEM_CRASH_CHECK 12
|
||||
//#define ERROR_SUBSYSTEM_FLIP 13
|
||||
#define ERROR_SUBSYSTEM_AUTOTUNE 14
|
||||
//#define ERROR_SUBSYSTEM_FLIP 13 // Remove
|
||||
//#define ERROR_SUBSYSTEM_PARACHUTE 15 // Remove
|
||||
#define ERROR_SUBSYSTEM_EKFCHECK 16
|
||||
#define ERROR_SUBSYSTEM_FAILSAFE_EKFINAV 17
|
||||
|
|
|
@ -285,7 +285,7 @@ bool Sub::should_disarm_on_failsafe()
|
|||
return !ap.auto_armed;
|
||||
break;
|
||||
default:
|
||||
// used for AltHold, Guided, Loiter, RTL, Circle, Drift, Sport, Flip, Autotune, PosHold
|
||||
// used for AltHold, Guided, Loiter, RTL, Circle, Drift, Sport, Flip, PosHold
|
||||
// if landed disarm
|
||||
// return ap.land_complete;
|
||||
return false;
|
||||
|
|
|
@ -57,12 +57,6 @@ bool Sub::set_mode(control_mode_t mode, mode_reason_t reason)
|
|||
success = surface_init(ignore_checks);
|
||||
break;
|
||||
|
||||
#if AUTOTUNE_ENABLED == ENABLED
|
||||
case AUTOTUNE:
|
||||
success = autotune_init(ignore_checks);
|
||||
break;
|
||||
#endif
|
||||
|
||||
#if POSHOLD_ENABLED == ENABLED
|
||||
case POSHOLD:
|
||||
success = poshold_init(ignore_checks);
|
||||
|
@ -150,12 +144,6 @@ void Sub::update_flight_mode()
|
|||
surface_run();
|
||||
break;
|
||||
|
||||
#if AUTOTUNE_ENABLED == ENABLED
|
||||
case AUTOTUNE:
|
||||
autotune_run();
|
||||
break;
|
||||
#endif
|
||||
|
||||
#if POSHOLD_ENABLED == ENABLED
|
||||
case POSHOLD:
|
||||
poshold_run();
|
||||
|
@ -174,12 +162,6 @@ void Sub::update_flight_mode()
|
|||
// exit_mode - high level call to organise cleanup as a flight mode is exited
|
||||
void Sub::exit_mode(control_mode_t old_control_mode, control_mode_t new_control_mode)
|
||||
{
|
||||
#if AUTOTUNE_ENABLED == ENABLED
|
||||
if (old_control_mode == AUTOTUNE) {
|
||||
autotune_stop();
|
||||
}
|
||||
#endif
|
||||
|
||||
// stop mission when we leave auto mode
|
||||
if (old_control_mode == AUTO) {
|
||||
if (mission.state() == AP_Mission::MISSION_RUNNING) {
|
||||
|
@ -284,9 +266,6 @@ void Sub::print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode)
|
|||
case OF_LOITER:
|
||||
port->print("OF_LOITER");
|
||||
break;
|
||||
case AUTOTUNE:
|
||||
port->print("AUTOTUNE");
|
||||
break;
|
||||
case POSHOLD:
|
||||
port->print("POSHOLD");
|
||||
break;
|
||||
|
|
|
@ -139,11 +139,6 @@ void Sub::init_disarm_motors()
|
|||
}
|
||||
}
|
||||
|
||||
#if AUTOTUNE_ENABLED == ENABLED
|
||||
// save auto tuned parameters
|
||||
autotune_save_tuning_gains();
|
||||
#endif
|
||||
|
||||
// log disarm to the dataflash
|
||||
Log_Write_Event(DATA_DISARMED);
|
||||
|
||||
|
|
|
@ -280,25 +280,6 @@ void Sub::do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
|
|||
}
|
||||
break;
|
||||
|
||||
#if AUTOTUNE_ENABLED == ENABLED
|
||||
case AUXSW_AUTOTUNE:
|
||||
// turn on auto tuner
|
||||
switch (ch_flag) {
|
||||
case AUX_SWITCH_LOW:
|
||||
case AUX_SWITCH_MIDDLE:
|
||||
// restore flight mode based on flight mode switch position
|
||||
if (control_mode == AUTOTUNE) {
|
||||
// reset_control_switch();
|
||||
}
|
||||
break;
|
||||
case AUX_SWITCH_HIGH:
|
||||
// start an autotuning session
|
||||
set_mode(AUTOTUNE);
|
||||
break;
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
|
||||
case AUXSW_LAND:
|
||||
// Do nothing for Sub
|
||||
|
||||
|
|
|
@ -3,7 +3,6 @@
|
|||
|
||||
/*
|
||||
* tuning.pde - function to update various parameters in flight using the ch6 tuning knob
|
||||
* This should not be confused with the AutoTune feature which can bve found in control_autotune.pde
|
||||
*/
|
||||
|
||||
// tuning - updates parameters based on the ch6 tuning knob's position
|
||||
|
|
Loading…
Reference in New Issue