mirror of https://github.com/ArduPilot/ardupilot
Replay: add to replay_results.txt when run with --check
This commit is contained in:
parent
c57b4f9c8c
commit
f79ae4b749
|
@ -254,6 +254,8 @@ private:
|
|||
float value;
|
||||
} user_parameters[100];
|
||||
|
||||
const char *log_filename = NULL;
|
||||
|
||||
void set_ins_update_rate(uint16_t update_rate);
|
||||
|
||||
void usage(void);
|
||||
|
@ -499,6 +501,9 @@ void Replay::setup()
|
|||
|
||||
hal.console->printf("Processing log %s\n", filename);
|
||||
|
||||
// remember filename for reporting
|
||||
log_filename = filename;
|
||||
|
||||
if (update_rate == 0) {
|
||||
update_rate = find_update_rate(filename);
|
||||
}
|
||||
|
@ -984,6 +989,17 @@ void Replay::report_checks(void)
|
|||
if (tolerance_euler < 0.01f) {
|
||||
tolerance_euler = 0.01f;
|
||||
}
|
||||
FILE *f = fopen("replay_results.txt","a");
|
||||
if (f != NULL) {
|
||||
fprintf(f, "%s %.3f %.3f %.3f %.3f %.3f\n",
|
||||
log_filename,
|
||||
check_result.max_roll_error,
|
||||
check_result.max_pitch_error,
|
||||
check_result.max_yaw_error,
|
||||
check_result.max_pos_error,
|
||||
check_result.max_vel_error);
|
||||
fclose(f);
|
||||
}
|
||||
if (check_result.max_roll_error > tolerance_euler) {
|
||||
printf("Roll error %.2f > %.2f\n", check_result.max_roll_error, tolerance_euler);
|
||||
failed = true;
|
||||
|
|
Loading…
Reference in New Issue