mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_Tuning: removed controller error messages
these are replaced by the SRate in PID messages
This commit is contained in:
parent
e715972264
commit
9eab217081
@ -189,9 +189,6 @@ void AP_Tuning::check_input(uint8_t flightmode)
|
|||||||
last_channel_value = chan_value;
|
last_channel_value = chan_value;
|
||||||
}
|
}
|
||||||
|
|
||||||
// check for controller error
|
|
||||||
check_controller_error();
|
|
||||||
|
|
||||||
if (fabsf(chan_value - last_channel_value) < 0.01) {
|
if (fabsf(chan_value - last_channel_value) < 0.01) {
|
||||||
// ignore changes of less than 1%
|
// ignore changes of less than 1%
|
||||||
return;
|
return;
|
||||||
@ -335,19 +332,3 @@ const char *AP_Tuning::get_tuning_name(uint8_t parm)
|
|||||||
}
|
}
|
||||||
return "UNKNOWN";
|
return "UNKNOWN";
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
|
||||||
check for controller error
|
|
||||||
*/
|
|
||||||
void AP_Tuning::check_controller_error(void)
|
|
||||||
{
|
|
||||||
float err = controller_error(current_parm);
|
|
||||||
if (err > error_threshold && !mid_point_wait && error_threshold > 0) {
|
|
||||||
uint32_t now = AP_HAL::millis();
|
|
||||||
if (now - last_controller_error_ms > 2000 && hal.util->get_soft_armed()) {
|
|
||||||
AP_Notify::events.tune_error = 1;
|
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "Tuning: error %.2f", (double)err);
|
|
||||||
last_controller_error_ms = now;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
@ -80,9 +80,6 @@ private:
|
|||||||
// last flight mode we were tuning in
|
// last flight mode we were tuning in
|
||||||
uint8_t last_flightmode;
|
uint8_t last_flightmode;
|
||||||
|
|
||||||
// last time we reported controller error
|
|
||||||
uint32_t last_controller_error_ms;
|
|
||||||
|
|
||||||
const tuning_set *tuning_sets;
|
const tuning_set *tuning_sets;
|
||||||
const tuning_name *tuning_names;
|
const tuning_name *tuning_names;
|
||||||
|
|
||||||
@ -92,7 +89,6 @@ private:
|
|||||||
void save_parameters(void);
|
void save_parameters(void);
|
||||||
void revert_parameters(void);
|
void revert_parameters(void);
|
||||||
const char *get_tuning_name(uint8_t parm);
|
const char *get_tuning_name(uint8_t parm);
|
||||||
void check_controller_error(void);
|
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
// virtual functions that must be implemented in vehicle subclass
|
// virtual functions that must be implemented in vehicle subclass
|
||||||
@ -100,7 +96,6 @@ protected:
|
|||||||
virtual void save_value(uint8_t parm) = 0;
|
virtual void save_value(uint8_t parm) = 0;
|
||||||
virtual void reload_value(uint8_t parm) = 0;
|
virtual void reload_value(uint8_t parm) = 0;
|
||||||
virtual void set_value(uint8_t parm, float value) = 0;
|
virtual void set_value(uint8_t parm, float value) = 0;
|
||||||
virtual float controller_error(uint8_t parm) = 0;
|
|
||||||
|
|
||||||
// parmset is in vehicle subclass var table
|
// parmset is in vehicle subclass var table
|
||||||
AP_Int16 parmset;
|
AP_Int16 parmset;
|
||||||
|
Loading…
Reference in New Issue
Block a user