Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_GPS: decouple status enumeration from MAVLink fix types #23229

Merged
merged 1 commit into from
Mar 22, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
20 changes: 20 additions & 0 deletions libraries/AP_GPS/AP_GPS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -87,6 +87,26 @@ const char AP_GPS::_initialisation_blob[] =
"" // to compile we need *some_initialiser if all backends compiled out
;

#if HAL_GCS_ENABLED
// ensure that our GPS_Status enumeration is 1:1 with the mavlink
// numbers of the same fix type. This allows us to do a simple cast
// from one to the other when sending GPS mavlink messages, rather
// than having some sort of mapping function from our internal
// enumeration into the mavlink enumeration. Doing things this way
// has two advantages - in the future we could add that mapping
// function and change our enumeration, and the other is that it
// allows us to build the GPS library without having the mavlink
// headers built (for example, in AP_Periph we shouldn't need mavlink
// headers).
static_assert((uint32_t)AP_GPS::GPS_Status::NO_GPS == (uint32_t)GPS_FIX_TYPE_NO_GPS, "NO_GPS incorrect");
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Wanna do static_cast<std::underlying_type>>? This has the advantage of compiler automatically sizing them for you.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Wanna do static_cast<std::underlying_type>>? This has the advantage of compiler automatically sizing them for you.

I've got a strong dislike for static casts - I find they make the code rather less readable. I'd rather not encourage their use unless there's a strong technical advantage.

Not that I'm saying these casts currently are particularly readable...

Copy link
Collaborator

@Ryanf55 Ryanf55 Mar 17, 2023

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

What do you think about adding a utility to do the conversions that matches the signature of std::to_underlying. It can be constexpr still but improves readability and removes the assumption about the size of enum.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

What do you think about adding a utility to do the conversions that matches the signature of std::to_underlying. It can be constexpr still but improves readability and removes the assumption about the size of enum.

Could you put together a patch on top of this one showing what you mean, please?

Copy link
Collaborator

@Ryanf55 Ryanf55 Mar 17, 2023

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Here's my attempt. I'd feel a little more comfortable about it if they were both enum class type. Maybe not using the built in == operator would make the function less likely to be misused.

From 0ba97fa1875b2521470e2033c59ebc737438ce17 Mon Sep 17 00:00:00 2001
From: Ryan Friedman <ryanfriedman5410+github@gmail.com>
Date: Thu, 16 Mar 2023 22:30:48 -0600
Subject: [PATCH] AP_GPS: Use underlying_type as constexpr comparison

Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
---
 libraries/AP_GPS/AP_GPS.cpp | 19 ++++++++++++-------
 libraries/AP_GPS/AP_GPS.h   |  5 +++++
 2 files changed, 17 insertions(+), 7 deletions(-)

diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp
index 95a590693d..487c6253a0 100644
--- a/libraries/AP_GPS/AP_GPS.cpp
+++ b/libraries/AP_GPS/AP_GPS.cpp
@@ -98,13 +98,18 @@ const char AP_GPS::_initialisation_blob[] =
 // allows us to build the GPS library without having the mavlink
 // headers built (for example, in AP_Periph we shouldn't need mavlink
 // headers).
-static_assert((uint32_t)AP_GPS::GPS_Status::NO_GPS == (uint32_t)GPS_FIX_TYPE_NO_GPS, "NO_GPS incorrect");
-static_assert((uint32_t)AP_GPS::GPS_Status::NO_FIX == (uint32_t)GPS_FIX_TYPE_NO_FIX, "NO_FIX incorrect");
-static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_2D == (uint32_t)GPS_FIX_TYPE_2D_FIX, "FIX_2D incorrect");
-static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_3D == (uint32_t)GPS_FIX_TYPE_3D_FIX, "FIX_3D incorrect");
-static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_3D_DGPS == (uint32_t)GPS_FIX_TYPE_DGPS, "FIX_DGPS incorrect");
-static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_3D_RTK_FLOAT == (uint32_t)GPS_FIX_TYPE_RTK_FLOAT, "FIX_RTK_FLOAT incorrect");
-static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_3D_RTK_FIXED == (uint32_t)GPS_FIX_TYPE_RTK_FIXED, "FIX_RTK_FIXED incorrect");
+static constexpr bool operator==(AP_GPS::GPS_Status a, GPS_FIX_TYPE b) {
+    return AP_GPS::to_underlying(a) == to_underlying(b);
+
+}
+
+static_assert(AP_GPS::GPS_Status::NO_GPS == GPS_FIX_TYPE_NO_GPS, "NO_GPS incorrect");
+static_assert(AP_GPS::GPS_Status::NO_FIX == GPS_FIX_TYPE_NO_FIX, "NO_FIX incorrect");
+static_assert(AP_GPS::GPS_Status::GPS_OK_FIX_2D == GPS_FIX_TYPE_2D_FIX, "FIX_2D incorrect");
+static_assert(AP_GPS::GPS_Status::GPS_OK_FIX_3D == GPS_FIX_TYPE_3D_FIX, "FIX_3D incorrect");
+static_assert(AP_GPS::GPS_Status::GPS_OK_FIX_3D_DGPS == GPS_FIX_TYPE_DGPS, "FIX_DGPS incorrect");
+static_assert(AP_GPS::GPS_Status::GPS_OK_FIX_3D_RTK_FLOAT == GPS_FIX_TYPE_RTK_FLOAT, "FIX_RTK_FLOAT incorrect");
+static_assert(AP_GPS::GPS_Status::GPS_OK_FIX_3D_RTK_FIXED == GPS_FIX_TYPE_RTK_FIXED, "FIX_RTK_FIXED incorrect");
 
 // prevent additions without thinking about this equivalence.  Note
 // that the MAVLink enumeration has values we don't use here.
diff --git a/libraries/AP_GPS/AP_GPS.h b/libraries/AP_GPS/AP_GPS.h
index 25c138a0fb..528d489190 100644
--- a/libraries/AP_GPS/AP_GPS.h
+++ b/libraries/AP_GPS/AP_GPS.h
@@ -16,6 +16,7 @@
 
 #include <AP_HAL/AP_HAL.h>
 #include <inttypes.h>
+#include <type_traits>
 #include <AP_Common/AP_Common.h>
 #include <AP_Common/Location.h>
 #include <AP_Param/AP_Param.h>
@@ -147,6 +148,10 @@ public:
         GPS_OK_FIX_3D_RTK_FIXED = 6, ///< Receiving valid messages and 3D RTK Fixed
     };
 
+    static constexpr std::underlying_type<GPS_Status>::type to_underlying(GPS_Status e) noexcept {
+        return static_cast<std::underlying_type<GPS_Status>::type>(e);
+    }
+
     // GPS navigation engine settings. Not all GPS receivers support
     // this
     enum GPS_Engine_Setting {
-- 
2.34.1

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

OK, thanks for the patch. I think I understand it. I'd rather not, however :-)

I'll bring it up in the DevCall to see if other people are keen.

We are gradually moving over to using enum class :-)

static_assert((uint32_t)AP_GPS::GPS_Status::NO_FIX == (uint32_t)GPS_FIX_TYPE_NO_FIX, "NO_FIX incorrect");
static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_2D == (uint32_t)GPS_FIX_TYPE_2D_FIX, "FIX_2D incorrect");
static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_3D == (uint32_t)GPS_FIX_TYPE_3D_FIX, "FIX_3D incorrect");
static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_3D_DGPS == (uint32_t)GPS_FIX_TYPE_DGPS, "FIX_DGPS incorrect");
static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_3D_RTK_FLOAT == (uint32_t)GPS_FIX_TYPE_RTK_FLOAT, "FIX_RTK_FLOAT incorrect");
static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_3D_RTK_FIXED == (uint32_t)GPS_FIX_TYPE_RTK_FIXED, "FIX_RTK_FIXED incorrect");
#endif

AP_GPS *AP_GPS::_singleton;

// table of user settable parameters
Expand Down
17 changes: 9 additions & 8 deletions libraries/AP_GPS/AP_GPS.h
Original file line number Diff line number Diff line change
Expand Up @@ -135,15 +135,16 @@ class AP_GPS
#endif
};

/// GPS status codes
/// GPS status codes. These are kept aligned with MAVLink by
/// static_assert in AP_GPS.cpp
enum GPS_Status {
NO_GPS = GPS_FIX_TYPE_NO_GPS, ///< No GPS connected/detected
NO_FIX = GPS_FIX_TYPE_NO_FIX, ///< Receiving valid GPS messages but no lock
GPS_OK_FIX_2D = GPS_FIX_TYPE_2D_FIX, ///< Receiving valid messages and 2D lock
GPS_OK_FIX_3D = GPS_FIX_TYPE_3D_FIX, ///< Receiving valid messages and 3D lock
GPS_OK_FIX_3D_DGPS = GPS_FIX_TYPE_DGPS, ///< Receiving valid messages and 3D lock with differential improvements
GPS_OK_FIX_3D_RTK_FLOAT = GPS_FIX_TYPE_RTK_FLOAT, ///< Receiving valid messages and 3D RTK Float
GPS_OK_FIX_3D_RTK_FIXED = GPS_FIX_TYPE_RTK_FIXED, ///< Receiving valid messages and 3D RTK Fixed
NO_GPS = 0, ///< No GPS connected/detected
NO_FIX = 1, ///< Receiving valid GPS messages but no lock
GPS_OK_FIX_2D = 2, ///< Receiving valid messages and 2D lock
GPS_OK_FIX_3D = 3, ///< Receiving valid messages and 3D lock
GPS_OK_FIX_3D_DGPS = 4, ///< Receiving valid messages and 3D lock with differential improvements
GPS_OK_FIX_3D_RTK_FLOAT = 5, ///< Receiving valid messages and 3D RTK Float
GPS_OK_FIX_3D_RTK_FIXED = 6, ///< Receiving valid messages and 3D RTK Fixed
};

// GPS navigation engine settings. Not all GPS receivers support
Expand Down