Browse Source

GNSS sensor component

Signed-off-by: Piotr Zyskowski <[email protected]>
Piotr Zyskowski 3 years ago
parent
commit
fedf1bad32

+ 100 - 0
Gems/ROS2/Code/Source/GNSS/GNSSFormatConversions.cpp

@@ -0,0 +1,100 @@
+/*
+ * Copyright (c) Contributors to the Open 3D Engine Project.
+ * For complete copyright and license terms please see the LICENSE at the root of this distribution.
+ *
+ * SPDX-License-Identifier: Apache-2.0 OR MIT
+ *
+ */
+
+#include "GNSSFormatConversions.h"
+
+constexpr double earthSemimajorAxis = 6378137.0f;
+constexpr double reciprocalFlattening = 1 / 298.257223563f;
+constexpr double earthSemiminorAxis = earthSemimajorAxis * (1.0f - reciprocalFlattening);
+constexpr double firstEccentricitySquared = 2 * reciprocalFlattening - reciprocalFlattening * reciprocalFlattening;
+constexpr double secondEccentrictySquared = reciprocalFlattening * (2.0f - reciprocalFlattening) / ((1.0f - reciprocalFlattening) * (1.0f - reciprocalFlattening));
+
+// Based on http://wiki.gis.com/wiki/index.php/Geodetic_system
+namespace ROS2::GNSS {
+    float Rad2Deg(float rad) {
+        return rad * 180.0f / AZ::Constants::Pi;
+    }
+
+    float Deg2Rad(float deg) {
+        return deg * AZ::Constants::Pi / 180.0f;
+    }
+
+    AZ::Vector3 WGS84ToECEF(const AZ::Vector3& latitudeLongitudeAltitude) {
+        const double latitudeRad = Deg2Rad(latitudeLongitudeAltitude.GetX());
+        const double longitudeRad = Deg2Rad(latitudeLongitudeAltitude.GetY());
+        const double altitude = latitudeLongitudeAltitude.GetZ();
+
+        const double helper = AZStd::sqrt(1.0f - firstEccentricitySquared * AZStd::sin(latitudeRad) * AZStd::sin(latitudeRad));
+
+        const double X = (earthSemimajorAxis / helper + altitude) * AZStd::cos(latitudeRad) * AZStd::cos(longitudeRad);
+        const double Y = (earthSemimajorAxis / helper + altitude) * AZStd::cos(latitudeRad) * AZStd::sin(longitudeRad);
+        const double Z = (earthSemimajorAxis * (1.0f - firstEccentricitySquared) / helper + altitude) * AZStd::sin(latitudeRad);
+
+        return {static_cast<float>(X), static_cast<float>(Y), static_cast<float>(Z)};
+    }
+
+    AZ::Vector3 ECEFToENU(const AZ::Vector3& referenceLatitudeLongitudeAltitude, const AZ::Vector3& ECEFPoint) {
+        AZ::Vector3 referencePointInECEF = WGS84ToECEF(referenceLatitudeLongitudeAltitude);
+        AZ::Vector3 pointToReferencePointECEF = ECEFPoint - referencePointInECEF;
+
+        float referenceLatitudeRad = Deg2Rad(referenceLatitudeLongitudeAltitude.GetX());
+        float referenceLongitudeRad = Deg2Rad(referenceLatitudeLongitudeAltitude.GetY());
+
+        return {
+                -AZStd::sin(referenceLongitudeRad) * pointToReferencePointECEF.GetX() + AZStd::cos(referenceLongitudeRad) * pointToReferencePointECEF.GetY(),
+                -AZStd::sin(referenceLatitudeRad) * AZStd::cos(referenceLongitudeRad) * pointToReferencePointECEF.GetX() - AZStd::sin(referenceLatitudeRad) * AZStd::sin(referenceLongitudeRad) * pointToReferencePointECEF.GetY() + AZStd::cos(referenceLatitudeRad) * pointToReferencePointECEF.GetZ(),
+                AZStd::cos(referenceLatitudeRad) * AZStd::cos(referenceLongitudeRad) * pointToReferencePointECEF.GetX() + AZStd::cos(referenceLatitudeRad) * AZStd::sin(referenceLongitudeRad) * pointToReferencePointECEF.GetY() + AZStd::sin(referenceLatitudeRad) * pointToReferencePointECEF.GetZ(),
+        };
+    }
+
+    AZ::Vector3 ENUToECEF(const AZ::Vector3& referenceLatitudeLongitudeAltitude, const AZ::Vector3& ENUPoint) {
+        AZ::Vector3 referenceECEF = WGS84ToECEF(referenceLatitudeLongitudeAltitude);
+
+        const float referenceLatitudeRad = Deg2Rad(referenceLatitudeLongitudeAltitude.GetX());
+        const float referenceLongitudeRad = Deg2Rad(referenceLatitudeLongitudeAltitude.GetY());
+        const float e = ENUPoint.GetX();
+        const float n = ENUPoint.GetY();
+        const float u = ENUPoint.GetZ();
+
+        return {-AZStd::sin(referenceLongitudeRad) * e - AZStd::cos(referenceLongitudeRad) * AZStd::sin(referenceLatitudeRad) * n + AZStd::cos(referenceLongitudeRad) * AZStd::cos(referenceLatitudeRad) * u + referenceECEF.GetX(),
+                 AZStd::cos(referenceLongitudeRad) * e - AZStd::sin(referenceLongitudeRad) * AZStd::sin(referenceLatitudeRad) * n + AZStd::cos(referenceLatitudeRad) * AZStd::sin(referenceLongitudeRad) * u + referenceECEF.GetY(),
+                 AZStd::cos(referenceLatitudeRad) * n + AZStd::sin(referenceLatitudeRad) * u + referenceECEF.GetZ()};
+    }
+
+    AZ::Vector3 ECEFToWGS84(const AZ::Vector3& ECFEPoint) {
+        const double x = ECFEPoint.GetX();
+        const double y = ECFEPoint.GetY();
+        const double z = ECFEPoint.GetZ();
+
+        const double radiusSquared = x * x + y * y;
+        const double radius = AZStd::sqrt(radiusSquared);
+
+        const double E2 = earthSemimajorAxis * earthSemimajorAxis - earthSemiminorAxis * earthSemiminorAxis;
+        const double F = 54.0f * earthSemiminorAxis * earthSemiminorAxis * z * z;
+        const double G = radiusSquared + (1.0f - firstEccentricitySquared) * z * z - firstEccentricitySquared * E2;
+        const double c = (firstEccentricitySquared * firstEccentricitySquared * F * radiusSquared) / (G * G * G);
+        const double s = std::cbrt(1.0f + c + AZStd::sqrt(c * c + 2.0f * c));
+        const double P = F / (3.0f * (s + 1.0f / s + 1.0f) * (s + 1.0f / s + 1.0f) * G * G);
+        const double Q = AZStd::sqrt(1.0f + 2.0f * firstEccentricitySquared * firstEccentricitySquared * P);
+
+        const double ro = -(firstEccentricitySquared * P * radius) / (1.0f + Q) +
+                AZStd::sqrt((earthSemimajorAxis * earthSemimajorAxis / 2.0f) * (1.0f + 1.0f / Q) -
+                            ((1.0f - firstEccentricitySquared) * P * z * z) / (Q * (1.0f + Q)) - P * radiusSquared / 2.0f);
+        const double tmp = (radius - firstEccentricitySquared * ro) * (radius - firstEccentricitySquared * ro);
+        const double U = AZStd::sqrt(tmp + z * z);
+        const double V = AZStd::sqrt(tmp + (1.0f - firstEccentricitySquared) * z * z);
+        const double zo = (earthSemiminorAxis * earthSemiminorAxis * z) / (earthSemimajorAxis * V);
+
+        const double latitude = AZStd::atan((z + secondEccentrictySquared * zo) / radius);
+        const double longitude = AZStd::atan2(y, x);
+        const double altitude = U * (1.0f - earthSemiminorAxis * earthSemiminorAxis / (earthSemimajorAxis * V));
+
+        return {Rad2Deg(static_cast<float>(latitude)), Rad2Deg(static_cast<float>(longitude)), static_cast<float>(altitude)};
+    }
+
+} // namespace ROS2::GNSS

+ 49 - 0
Gems/ROS2/Code/Source/GNSS/GNSSFormatConversions.h

@@ -0,0 +1,49 @@
+/*
+ * Copyright (c) Contributors to the Open 3D Engine Project.
+ * For complete copyright and license terms please see the LICENSE at the root of this distribution.
+ *
+ * SPDX-License-Identifier: Apache-2.0 OR MIT
+ *
+ */
+
+#pragma once
+
+#include "AzCore/Math/Matrix4x4.h"
+
+namespace ROS2::GNSS {
+    //! Converts radians to degrees
+    float Rad2Deg(float rad);
+
+    //! Converts degrees to radians
+    float Deg2Rad(float deg);
+
+    //! Converts point in 1984 World Geodetic System (GS84) to Earth Centred Earth Fixed (ECEF)
+    //! @param latitudeLongitudeAltitude - point's latitude, longitude and altitude as 3d vector.
+    //!     latitude and longitude are in decimal degrees
+    //!     altitude is in meters
+    //! @return 3d vector of ECEF coordinates.
+    AZ::Vector3 WGS84ToECEF(const AZ::Vector3& latitudeLongitudeAltitude);
+
+    //! Converts Earth Centred Earth Fixed (ECEF) coordinates to local east, north, up (ENU)
+    //! @param referenceLatitudeLongitudeAltitude - reference point's latitude, longitude and altitude as 3d vector.
+    //!     latitude and longitude are in decimal degrees
+    //!     altitude is in meters
+    //! @param ECEFPoint - ECEF point to bo converted.
+    //! @return 3d vector of local east, north, up (ENU) coordinates.
+    AZ::Vector3 ECEFToENU(const AZ::Vector3& referenceLatitudeLongitudeAltitude, const AZ::Vector3& ECEFPoint);
+
+    //! Converts local east, north, up (ENU) coordinates to Earth Centred Earth Fixed (ECEF)
+    //! @param referenceLatitudeLongitudeAltitude - reference point's latitude, longitude and altitude as 3d vector.
+    //!     latitude and longitude are in decimal degrees
+    //!     altitude is in meters
+    //! @param ENUPoint - ENU point to bo converted.
+    //! @return 3d vector of ECEF coordinates.
+    AZ::Vector3 ENUToECEF(const AZ::Vector3& referenceLatitudeLongitudeAltitude, const AZ::Vector3& ENUPoint);
+
+    //! Converts point in Earth Centred Earth Fixed (ECEF) to  984 World Geodetic System (GS84)
+    //! @param ECEFPoint - ECEF point to bo converted.
+    //! @return point's latitude, longitude and altitude as 3d vector.
+    //!     latitude and longitude are in decimal degrees
+    //!     altitude is in meters
+    AZ::Vector3 ECEFToWGS84(const AZ::Vector3& ECFEPoint);
+} // namespace ROS2::GNSS

+ 106 - 0
Gems/ROS2/Code/Source/GNSS/ROS2GNSSSensorComponent.cpp

@@ -0,0 +1,106 @@
+/*
+ * Copyright (c) Contributors to the Open 3D Engine Project.
+ * For complete copyright and license terms please see the LICENSE at the root of this distribution.
+ *
+ * SPDX-License-Identifier: Apache-2.0 OR MIT
+ *
+ */
+
+#include "GNSS/ROS2GNSSSensorComponent.h"
+#include "Frame/ROS2FrameComponent.h"
+#include "ROS2/ROS2Bus.h"
+#include "Utilities/ROS2Conversions.h"
+#include "Utilities/ROS2Names.h"
+#include "AzCore/Math/Matrix4x4.h"
+
+#include <AzCore/Serialization/EditContext.h>
+#include <AzCore/Serialization/EditContextConstants.inl>
+
+#include "GNSSFormatConversions.h"
+
+namespace ROS2
+{
+    namespace Internal
+    {
+        const char* kGNSSMsgType = "sensor_msgs::msg::NavSatFix";
+    }
+
+    void ROS2GNSSSensorComponent::Reflect(AZ::ReflectContext* context)
+    {
+        if (AZ::SerializeContext* serialize = azrtti_cast<AZ::SerializeContext*>(context))
+        {
+            serialize->Class<ROS2GNSSSensorComponent, ROS2SensorComponent>()
+                    ->Version(1)
+                    ->Field("gnssOriginLatitude", &ROS2GNSSSensorComponent::m_gnssOriginLatitudeDeg)
+                    ->Field("gnssOriginLongitude", &ROS2GNSSSensorComponent::m_gnssOriginLongitudeDeg)
+                    ->Field("gnssOriginAltitude", &ROS2GNSSSensorComponent::m_gnssOriginAltitude)
+                    ;
+
+            if (AZ::EditContext* ec = serialize->GetEditContext())
+            {
+                ec->Class<ROS2GNSSSensorComponent>("ROS2 GNSS Sensor", "GNSS sensor component")
+                        ->ClassElement(AZ::Edit::ClassElements::EditorData, "")
+                        ->Attribute(AZ::Edit::Attributes::AppearsInAddComponentMenu, AZ_CRC("Game"))
+                        ->DataElement(AZ::Edit::UIHandlers::Default, &ROS2GNSSSensorComponent::m_gnssOriginLatitudeDeg,
+                                      "Latitude offset", "GNSS latitude position offset in degrees")
+                        ->DataElement(AZ::Edit::UIHandlers::Default, &ROS2GNSSSensorComponent::m_gnssOriginLongitudeDeg,
+                                      "Longitude offset", "GNSS longitude position offset in degrees")
+                        ->DataElement(AZ::Edit::UIHandlers::Default, &ROS2GNSSSensorComponent::m_gnssOriginAltitude,
+                                      "Altitude offset", "GNSS altitude position offset in meters")
+                        ;
+            }
+        }
+    }
+
+    ROS2GNSSSensorComponent::ROS2GNSSSensorComponent()
+    {
+        PublisherConfiguration pc;
+        pc.m_type = Internal::kGNSSMsgType;
+        pc.m_topic = "gnss";
+        m_sensorConfiguration.m_frequency = 10;
+        m_sensorConfiguration.m_publishersConfigurations.insert(AZStd::make_pair(Internal::kGNSSMsgType, pc));
+    }
+
+    void ROS2GNSSSensorComponent::Activate()
+    {
+        ROS2SensorComponent::Activate();
+        auto ros2Node = ROS2Interface::Get()->GetNode();
+        AZ_Assert(m_sensorConfiguration.m_publishersConfigurations.size() == 1, "Invalid configuration of publishers for GNSS sensor");
+
+        const auto publisherConfig = m_sensorConfiguration.m_publishersConfigurations[Internal::kGNSSMsgType];
+        const auto fullTopic = ROS2Names::GetNamespacedName(GetNamespace(), publisherConfig.m_topic);
+        m_gnssPublisher = ros2Node->create_publisher<sensor_msgs::msg::NavSatFix>(fullTopic.data(), publisherConfig.GetQoS());
+
+        m_gnssMsg.header.frame_id = "gnss_frame_id";
+    }
+
+    void ROS2GNSSSensorComponent::Deactivate()
+    {
+        ROS2SensorComponent::Deactivate();
+        m_gnssPublisher.reset();
+    }
+
+    void ROS2GNSSSensorComponent::FrequencyTick()
+    {
+        const AZ::Vector3 currentPosition = GetCurrentPose().GetTranslation();
+        const AZ::Vector3 currentPositionECEF =
+                GNSS::ENUToECEF({m_gnssOriginLatitudeDeg, m_gnssOriginLongitudeDeg, m_gnssOriginAltitude},
+                                 currentPosition);
+        const AZ::Vector3 currentPositionWGS84 = GNSS::ECEFToWGS84(currentPositionECEF);
+
+        m_gnssMsg.latitude = currentPositionWGS84.GetX();
+        m_gnssMsg.longitude = currentPositionWGS84.GetY();
+        m_gnssMsg.altitude = currentPositionWGS84.GetZ();
+
+        m_gnssMsg.status.status = sensor_msgs::msg::NavSatStatus::STATUS_SBAS_FIX;
+        m_gnssMsg.status.service = sensor_msgs::msg::NavSatStatus::SERVICE_GALILEO;
+
+        m_gnssPublisher->publish(m_gnssMsg);
+    }
+
+    AZ::Transform ROS2GNSSSensorComponent::GetCurrentPose() const
+    {
+        auto ros2Frame = GetEntity()->FindComponent<ROS2FrameComponent>();
+        return ros2Frame->GetFrameTransform();
+    }
+} // namespace ROS2

+ 46 - 0
Gems/ROS2/Code/Source/GNSS/ROS2GNSSSensorComponent.h

@@ -0,0 +1,46 @@
+/*
+ * Copyright (c) Contributors to the Open 3D Engine Project.
+ * For complete copyright and license terms please see the LICENSE at the root of this distribution.
+ *
+ * SPDX-License-Identifier: Apache-2.0 OR MIT
+ *
+ */
+#pragma once
+
+#include "Sensor/ROS2SensorComponent.h"
+#include <AzCore/Math/Transform.h>
+#include <AzCore/Serialization/SerializeContext.h>
+#include <rclcpp/publisher.hpp>
+#include <sensor_msgs/msg/nav_sat_fix.hpp>
+
+namespace ROS2
+{
+    //! Global Navigation Satellite Systems (GNSS) sensor component class
+    //! It provides NavSatFix data of sensor's position in GNSS frame which is defined by GNSS origin offset
+    //! Offset is provided as latitude [deg], longitude [deg], altitude [m] of o3de global frame
+    //! It is assumed that o3de global frame overlaps with ENU coordinate system
+    class ROS2GNSSSensorComponent
+            : public ROS2SensorComponent
+    {
+    public:
+        AZ_COMPONENT(ROS2GNSSSensorComponent, "{55B4A299-7FA3-496A-88F0-764C75B0E9A7}", ROS2SensorComponent);
+        ROS2GNSSSensorComponent();
+        ~ROS2GNSSSensorComponent() = default;
+        static void Reflect(AZ::ReflectContext* context);
+        void Activate() override;
+        void Deactivate() override;
+
+    private:
+        float m_gnssOriginLatitudeDeg = 0.0f;
+        float m_gnssOriginLongitudeDeg = 0.0f;
+        float m_gnssOriginAltitude = 0.0f;
+
+        void FrequencyTick() override;
+
+        AZ::Transform GetCurrentPose() const;
+
+        std::shared_ptr<rclcpp::Publisher<sensor_msgs::msg::NavSatFix>> m_gnssPublisher;
+        sensor_msgs::msg::NavSatFix m_gnssMsg;
+    };
+
+}  // namespace ROS2

+ 2 - 0
Gems/ROS2/Code/Source/ROS2ModuleInterface.h

@@ -9,6 +9,7 @@
 
 
 #include "Frame/ROS2FrameComponent.h"
 #include "Frame/ROS2FrameComponent.h"
 #include "Imu/ROS2ImuSensorComponent.h"
 #include "Imu/ROS2ImuSensorComponent.h"
+#include "GNSS/ROS2GNSSSensorComponent.h"
 #include "Lidar/ROS2LidarSensorComponent.h"
 #include "Lidar/ROS2LidarSensorComponent.h"
 #include "RobotControl/ROS2RobotControlComponent.h"
 #include "RobotControl/ROS2RobotControlComponent.h"
 #include "ROS2SystemComponent.h"
 #include "ROS2SystemComponent.h"
@@ -34,6 +35,7 @@ namespace ROS2
                 ROS2SystemComponent::CreateDescriptor(),
                 ROS2SystemComponent::CreateDescriptor(),
                 ROS2SensorComponent::CreateDescriptor(),
                 ROS2SensorComponent::CreateDescriptor(),
                 ROS2ImuSensorComponent::CreateDescriptor(),
                 ROS2ImuSensorComponent::CreateDescriptor(),
+                ROS2GNSSSensorComponent::CreateDescriptor(),
                 ROS2LidarSensorComponent::CreateDescriptor(),
                 ROS2LidarSensorComponent::CreateDescriptor(),
                 ROS2FrameComponent::CreateDescriptor(),
                 ROS2FrameComponent::CreateDescriptor(),
                 ROS2RobotControlComponent::CreateDescriptor()
                 ROS2RobotControlComponent::CreateDescriptor()

+ 78 - 0
Gems/ROS2/Code/Tests/GNSSTest.cpp

@@ -0,0 +1,78 @@
+#include <AzTest/AzTest.h>
+#include <AzCore/UnitTest/TestTypes.h>
+
+#include "GNSS/GNSSFormatConversions.h"
+
+namespace UnitTest {
+
+    class GNSSTest : public AllocatorsTestFixture {
+    };
+
+    TEST_F(GNSSTest, WGS84ToECEF) {
+        const std::vector<std::pair<AZ::Vector3, AZ::Vector3>> input_gold_set = {
+                { {10.0f, 20.0f, 300.0f}, {5903307.167667380f, 2148628.092761247f, 1100300.642188661f} },
+                { {-70.0f, 170.0f, 500.0f}, {-2154856.524084172f, 379959.3447517005f, -5971509.853428957f} },
+                { {50.0f, -120.0f, -100.0f}, {-2053899.906222906f, -3557458.991239029f, 4862712.433262121f} },
+        };
+        for (const auto& [input, goldResult] : input_gold_set) {
+            AZ::Vector3 result = ROS2::GNSS::WGS84ToECEF(input);
+            EXPECT_NEAR(result.GetX(), goldResult.GetX(), 1.0f);
+            EXPECT_NEAR(result.GetY(), goldResult.GetY(), 1.0f);
+            EXPECT_NEAR(result.GetZ(), goldResult.GetZ(), 1.0f);
+        }
+    }
+
+    TEST_F(GNSSTest, ECEFToENU) {
+        const std::vector<std::tuple<AZ::Vector3, AZ::Vector3, AZ::Vector3>> input_gold_set = {
+                { { -2053900.0f, -3557459.0f, 4862712.0f},
+                  {50.0f, -120.0f, -100.0f},
+                  {-0.076833f, -0.3202f, -0.2969f} },
+                { {5903307.167667380f, 2148628.092761247f, 1100300.642188661f},
+                  {11.0f, 21.0f, 400.0f},
+                  {-109638.9539891188f, -110428.2398398574f, -2004.501240225796f} },
+                { {-2154856.524084172f, 379959.3447517005f, -5971509.853428957f},
+                  {-72.0f, 169.0f, 1000.0f},
+                  {38187.58712786288f, 222803.8182465429f, -4497.428919329745f} },
+        };
+        for (const auto& [input, refWGS84, goldResult] : input_gold_set) {
+            AZ::Vector3 result = ROS2::GNSS::ECEFToENU(refWGS84, input);
+            EXPECT_NEAR(result.GetX(), goldResult.GetX(), 1.0f);
+            EXPECT_NEAR(result.GetY(), goldResult.GetY(), 1.0f);
+            EXPECT_NEAR(result.GetZ(), goldResult.GetZ(), 1.0f);
+        }
+    }
+
+    TEST_F(GNSSTest, ENUToECEF) {
+        const std::vector<std::tuple<AZ::Vector3, AZ::Vector3, AZ::Vector3>> input_gold_set = {
+                { {-0.076833f, -0.3202f, -0.2969f},
+                  {50.0f, -120.0f, -100.0f},
+                  {-2053900.0f, -3557459.0f, 4862712.0f} },
+                { {-109638.9539891188f, -110428.2398398574f, -2004.501240225796f},
+                  {11.0f, 21.0f, 400.0f},
+                  {5903307.167667380f, 2148628.092761247f, 1100300.642188661f} },
+                { {38187.58712786288f, 222803.8182465429f, -4497.428919329745f},
+                  {-72.0f, 169.0f, 1000.0f},
+                  {-2154856.524084172f, 379959.3447517005f, -5971509.853428957f} },
+        };
+        for (const auto& [ input, refWGS84, goldResult] : input_gold_set) {
+            AZ::Vector3 result = ROS2::GNSS::ENUToECEF(refWGS84, input);
+            EXPECT_NEAR(result.GetX(), goldResult.GetX(), 1.0f);
+            EXPECT_NEAR(result.GetY(), goldResult.GetY(), 1.0f);
+            EXPECT_NEAR(result.GetZ(), goldResult.GetZ(), 1.0f);
+        }
+    }
+
+    TEST_F(GNSSTest, ECEFToWSG84) {
+        const std::vector<std::pair<AZ::Vector3, AZ::Vector3>> input_gold_set = {
+                { {5903307.167667380f, 2148628.092761247f, 1100300.642188661f},   {10.0f, 20.0f, 300.0f}   },
+                { {-2154856.524084172f, 379959.3447517005f, -5971509.853428957f}, {-70.0f, 170.0f, 500.0f}  },
+                { {-2053899.906222906f, -3557458.991239029f, 4862712.433262121f}, {50.0f, -120.0f, -100.0f} },
+        };
+        for (const auto& [input, goldResult] : input_gold_set) {
+            AZ::Vector3 result = ROS2::GNSS::ECEFToWGS84(input);
+            EXPECT_NEAR(result.GetX(), goldResult.GetX(), 0.001f);
+            EXPECT_NEAR(result.GetY(), goldResult.GetY(), 0.001f);
+            EXPECT_NEAR(result.GetZ(), goldResult.GetZ(), 1.0f);
+        }
+    }
+}

+ 4 - 0
Gems/ROS2/Code/ros2_files.cmake

@@ -46,6 +46,10 @@ set(FILES
     Source/Utilities/ROS2Conversions.h
     Source/Utilities/ROS2Conversions.h
     Source/Utilities/ROS2Names.cpp
     Source/Utilities/ROS2Names.cpp
     Source/Utilities/ROS2Names.h
     Source/Utilities/ROS2Names.h
+    Source/GNSS/ROS2GNSSSensorComponent.cpp
+    Source/GNSS/ROS2GNSSSensorComponent.h
+    Source/GNSS/GNSSFormatConversions.cpp
+    Source/GNSS/GNSSFormatConversions.h
     Source/Imu/ROS2ImuSensorComponent.cpp
     Source/Imu/ROS2ImuSensorComponent.cpp
     Source/Imu/ROS2ImuSensorComponent.h
     Source/Imu/ROS2ImuSensorComponent.h
     Source/URDF/UrdfParser.cpp
     Source/URDF/UrdfParser.cpp

+ 1 - 0
Gems/ROS2/Code/ros2_tests_files.cmake

@@ -8,4 +8,5 @@ set(FILES
     Tests/UrdfParserTest.cpp
     Tests/UrdfParserTest.cpp
     Tests/FbxGeneratorTest.cpp
     Tests/FbxGeneratorTest.cpp
     Tests/UrdfToFbxConverterTest.cpp
     Tests/UrdfToFbxConverterTest.cpp
+    Tests/GNSSTest.cpp
 )
 )