From edac5e1a806598c98c35ecad524e53d30a347e58 Mon Sep 17 00:00:00 2001 From: "Dr.-Ing. Amilcar do Carmo Lucas" Date: Mon, 25 Feb 2019 01:12:26 +0100 Subject: [PATCH] Tools: replace location_offset() and get_distance() function calls with Location object member function calls This allows removing duplicated code --- Tools/Replay/Replay.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/Replay/Replay.cpp b/Tools/Replay/Replay.cpp index 5b752b5f8d..643da9fb7a 100644 --- a/Tools/Replay/Replay.cpp +++ b/Tools/Replay/Replay.cpp @@ -768,7 +768,7 @@ void Replay::log_check_solution(void) float pitch_error = degrees(fabsf(euler.y - check_state.euler.y)); float yaw_error = wrap_180_cd(100*degrees(fabsf(euler.z - check_state.euler.z)))*0.01f; float vel_error = (velocity - check_state.velocity).length(); - float pos_error = get_distance(check_state.pos, loc); + float pos_error = check_state.pos.get_distance(loc); check_result.max_roll_error = MAX(check_result.max_roll_error, roll_error); check_result.max_pitch_error = MAX(check_result.max_pitch_error, pitch_error);