mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 12:38:33 -04:00
Copter: Autotune log acceleration
This commit is contained in:
parent
b336ab4de7
commit
fe0d069eab
@ -580,7 +580,7 @@ private:
|
||||
void gcs_check_input(void);
|
||||
void gcs_send_text_P(gcs_severity severity, const prog_char_t *str);
|
||||
void do_erase_logs(void);
|
||||
void Log_Write_AutoTune(uint8_t axis, uint8_t tune_step, float rate_target, float rate_min, float rate_max, float new_gain_rp, float new_gain_rd, float new_gain_sp);
|
||||
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);
|
||||
void Log_Write_Current();
|
||||
void Log_Write_Optflow();
|
||||
|
@ -160,28 +160,30 @@ struct PACKED log_AutoTune {
|
||||
uint64_t time_us;
|
||||
uint8_t axis; // roll or pitch
|
||||
uint8_t tune_step; // tuning PI or D up or down
|
||||
float rate_target; // target achieved rotation rate
|
||||
float rate_min; // maximum achieved rotation rate
|
||||
float rate_max; // maximum achieved rotation rate
|
||||
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 Copter::Log_Write_AutoTune(uint8_t axis, uint8_t tune_step, float rate_target, float rate_min, float rate_max, float new_gain_rp, float new_gain_rd, float new_gain_sp)
|
||||
void Copter::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 : hal.scheduler->micros64(),
|
||||
axis : axis,
|
||||
tune_step : tune_step,
|
||||
rate_target : rate_target,
|
||||
rate_min : rate_min,
|
||||
rate_max : rate_max,
|
||||
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_gain_sp : new_gain_sp,
|
||||
new_ddt : new_ddt
|
||||
};
|
||||
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
@ -656,7 +658,7 @@ const struct LogStructure Copter::log_structure[] PROGMEM = {
|
||||
LOG_COMMON_STRUCTURES,
|
||||
#if AUTOTUNE_ENABLED == ENABLED
|
||||
{ LOG_AUTOTUNE_MSG, sizeof(log_AutoTune),
|
||||
"ATUN", "QBBffffff", "TimeUS,Axis,TuneStep,RateTarg,RateMin,RateMax,RP,RD,SP" },
|
||||
"ATUN", "QBBfffffff", "TimeUS,Axis,TuneStep,Targ,Min,Max,RP,RD,SP,ddt" },
|
||||
{ LOG_AUTOTUNEDETAILS_MSG, sizeof(log_AutoTuneDetails),
|
||||
"ATDE", "Qff", "TimeUS,Angle,Rate" },
|
||||
#endif
|
||||
|
@ -524,25 +524,25 @@ void Copter::autotune_attitude_control()
|
||||
if ((autotune_state.tune_type == AUTOTUNE_TYPE_SP_DOWN) || (autotune_state.tune_type == AUTOTUNE_TYPE_SP_UP)) {
|
||||
switch (autotune_state.axis) {
|
||||
case AUTOTUNE_AXIS_ROLL:
|
||||
Log_Write_AutoTune(autotune_state.axis, autotune_state.tune_type, autotune_target_angle, autotune_test_min, autotune_test_max, tune_roll_rp, tune_roll_rd, tune_roll_sp);
|
||||
Log_Write_AutoTune(autotune_state.axis, autotune_state.tune_type, autotune_target_angle, autotune_test_min, autotune_test_max, tune_roll_rp, tune_roll_rd, tune_roll_sp, autotune_test_accel_max);
|
||||
break;
|
||||
case AUTOTUNE_AXIS_PITCH:
|
||||
Log_Write_AutoTune(autotune_state.axis, autotune_state.tune_type, autotune_target_angle, autotune_test_min, autotune_test_max, tune_pitch_rp, tune_pitch_rd, tune_pitch_sp);
|
||||
Log_Write_AutoTune(autotune_state.axis, autotune_state.tune_type, autotune_target_angle, autotune_test_min, autotune_test_max, tune_pitch_rp, tune_pitch_rd, tune_pitch_sp, autotune_test_accel_max);
|
||||
break;
|
||||
case AUTOTUNE_AXIS_YAW:
|
||||
Log_Write_AutoTune(autotune_state.axis, autotune_state.tune_type, autotune_target_angle, autotune_test_min, autotune_test_max, tune_yaw_rp, tune_yaw_rLPF, tune_yaw_sp);
|
||||
Log_Write_AutoTune(autotune_state.axis, autotune_state.tune_type, autotune_target_angle, autotune_test_min, autotune_test_max, tune_yaw_rp, tune_yaw_rLPF, tune_yaw_sp, autotune_test_accel_max);
|
||||
break;
|
||||
}
|
||||
} else {
|
||||
switch (autotune_state.axis) {
|
||||
case AUTOTUNE_AXIS_ROLL:
|
||||
Log_Write_AutoTune(autotune_state.axis, autotune_state.tune_type, autotune_target_rate, autotune_test_min, autotune_test_max, tune_roll_rp, tune_roll_rd, tune_roll_sp);
|
||||
Log_Write_AutoTune(autotune_state.axis, autotune_state.tune_type, autotune_target_rate, autotune_test_min, autotune_test_max, tune_roll_rp, tune_roll_rd, tune_roll_sp, autotune_test_accel_max);
|
||||
break;
|
||||
case AUTOTUNE_AXIS_PITCH:
|
||||
Log_Write_AutoTune(autotune_state.axis, autotune_state.tune_type, autotune_target_rate, autotune_test_min, autotune_test_max, tune_pitch_rp, tune_pitch_rd, tune_pitch_sp);
|
||||
Log_Write_AutoTune(autotune_state.axis, autotune_state.tune_type, autotune_target_rate, autotune_test_min, autotune_test_max, tune_pitch_rp, tune_pitch_rd, tune_pitch_sp, autotune_test_accel_max);
|
||||
break;
|
||||
case AUTOTUNE_AXIS_YAW:
|
||||
Log_Write_AutoTune(autotune_state.axis, autotune_state.tune_type, autotune_target_rate, autotune_test_min, autotune_test_max, tune_yaw_rp, tune_yaw_rLPF, tune_yaw_sp);
|
||||
Log_Write_AutoTune(autotune_state.axis, autotune_state.tune_type, autotune_target_rate, autotune_test_min, autotune_test_max, tune_yaw_rp, tune_yaw_rLPF, tune_yaw_sp, autotune_test_accel_max);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user