From 76861eaa9b207b0dbf62865d911749583024acf9 Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Thu, 7 Dec 2023 00:10:04 -0700 Subject: [PATCH] AP_Common: Define units for locatoin data members Signed-off-by: Ryan Friedman --- libraries/AP_Common/Location.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Common/Location.h b/libraries/AP_Common/Location.h index 134a27e590af3..eab834e2d427f 100644 --- a/libraries/AP_Common/Location.h +++ b/libraries/AP_Common/Location.h @@ -15,9 +15,9 @@ class Location uint8_t loiter_xtrack : 1; // 0 to crosstrack from center of waypoint, 1 to crosstrack from tangent exit location // note that mission storage only stores 24 bits of altitude (~ +/- 83km) - int32_t alt; - int32_t lat; - int32_t lng; + int32_t alt; // in cm + int32_t lat; // in 1E7 degrees + int32_t lng; // in 1E7 degrees /// enumeration of possible altitude types enum class AltFrame {