From 526fd2ca4801e720bf604b9c131a1206b8a597f2 Mon Sep 17 00:00:00 2001 From: Rishabh Date: Fri, 3 Jan 2020 23:27:15 +0530 Subject: [PATCH] Rover: Changed logging of wp_bearing and nav_bearing to degrees --- APMrover2/Log.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/APMrover2/Log.cpp b/APMrover2/Log.cpp index ef1b8f61c562cb..c6e21606f64862 100644 --- a/APMrover2/Log.cpp +++ b/APMrover2/Log.cpp @@ -99,8 +99,8 @@ struct PACKED log_Nav_Tuning { LOG_PACKET_HEADER; uint64_t time_us; float wp_distance; - uint16_t wp_bearing_cd; - uint16_t nav_bearing_cd; + uint16_t wp_bearing; + uint16_t nav_bearing; uint16_t yaw; float xtrack_error; }; @@ -112,8 +112,8 @@ void Rover::Log_Write_Nav_Tuning() LOG_PACKET_HEADER_INIT(LOG_NTUN_MSG), time_us : AP_HAL::micros64(), wp_distance : control_mode->get_distance_to_destination(), - wp_bearing_cd : (uint16_t)wrap_360_cd(control_mode->wp_bearing() * 100), - nav_bearing_cd : (uint16_t)wrap_360_cd(control_mode->nav_bearing() * 100), + wp_bearing : (uint16_t)wrap_360(control_mode->wp_bearing()), + nav_bearing : (uint16_t)wrap_360(control_mode->nav_bearing()), yaw : (uint16_t)ahrs.yaw_sensor, xtrack_error : control_mode->crosstrack_error() };