소스 검색

Modified clock design, added new time source (#707)

* Modified clock design, added new time source
* Added one clock class with different time sources
* Added ROS 2 time source
* Added options to Registry to choose time source and enable/disable time publishing
* updated documentation

---------

Signed-off-by: Patryk Antosz <[email protected]>
Co-authored-by: Michał Pełka <[email protected]>
Co-authored-by: Steve Pham <[email protected]>
Patryk Antosz 1 년 전
부모
커밋
63fa847997

+ 26 - 0
Gems/ROS2/Code/Include/ROS2/Clock/ITimeSource.h

@@ -0,0 +1,26 @@
+/*
+ * 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 <builtin_interfaces/msg/time.hpp>
+
+namespace ROS2
+{
+    class ITimeSource
+    {
+    public:
+        virtual void Activate() = 0;
+        virtual void Deactivate() = 0;
+
+        virtual ~ITimeSource() = default;
+
+        //! Get time as ROS 2 message.
+        //! @see ROS2Requests::GetROSTimestamp() for more details.
+        virtual builtin_interfaces::msg::Time GetROSTimestamp() const = 0;
+    };
+} // namespace ROS2

+ 0 - 38
Gems/ROS2/Code/Include/ROS2/Clock/PhysicallyStableClock.h

@@ -1,38 +0,0 @@
-/*
- * 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 "SimulationClock.h"
-#include <AzCore/std/chrono/chrono.h>
-#include <AzFramework/Physics/Common/PhysicsEvents.h>
-#include <AzFramework/Physics/PhysicsSystem.h>
-#include <builtin_interfaces/msg/time.hpp>
-#include <rosgraph_msgs/msg/clock.hpp>
-
-namespace ROS2
-{
-    //! Simulation clock which changes source to physics of timestamps that are provided by \ref GetROSTimestamp.
-    //! The simulated clock is incremented with delta times that were simulated by physics.
-    //! Clock register and observes AZ::PhysicsScene and when simulation starts, it attaches and starts to count updates.
-    //! It is recommended to use with high-frequency sensors such as odometry and IMUs.
-    class PhysicallyStableClock : public SimulationClock
-    {
-    public:
-        // SimulationClock overrides ...
-        void Activate() override;
-        void Deactivate() override;
-        builtin_interfaces::msg::Time GetROSTimestamp() const override;
-
-        virtual ~PhysicallyStableClock() = default;
-
-    private:
-        double m_elapsed = 0;
-        AzPhysics::SceneEvents::OnSceneSimulationFinishHandler m_onSceneSimulationEvent;
-        AzPhysics::SystemEvents::OnSceneAddedEvent::Handler m_onSceneAdded;
-        AzPhysics::SystemEvents::OnSceneRemovedEvent::Handler m_onSceneRemoved;
-    };
-} // namespace ROS2

+ 45 - 0
Gems/ROS2/Code/Include/ROS2/Clock/ROS2Clock.h

@@ -0,0 +1,45 @@
+/*
+ * 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 "ITimeSource.h"
+#include <AzCore/std/chrono/chrono.h>
+#include <AzCore/std/smart_ptr/unique_ptr.h>
+#include <rclcpp/publisher.hpp>
+#include <rosgraph_msgs/msg/clock.hpp>
+
+namespace ROS2
+{
+    //! The ROS2Clock provides ROS timestamps as builtin_interface::msg::Time messages.
+    //! The clock can use different types of the time sources and publish the current
+    //! time to the ROS 2 `/clock/` topic. The published time can be used with
+    //! the /use_sim_time parameter set to true.
+    class ROS2Clock
+    {
+        static constexpr size_t FramesNumberForStats = 60;
+
+    public:
+        ROS2Clock();
+        ROS2Clock(AZStd::unique_ptr<ITimeSource> timeSource, bool publishClock);
+        ~ROS2Clock() = default;
+
+        void Activate();
+        void Deactivate();
+
+        builtin_interfaces::msg::Time GetROSTimestamp() const;
+
+        //! Update time in the ROS 2 ecosystem.
+        //! This will publish current time to the ROS 2 `/clock` topic, if Clock is configured to do it.
+        void Tick();
+
+    private:
+        rclcpp::Publisher<rosgraph_msgs::msg::Clock>::SharedPtr m_clockPublisher;
+        AZStd::unique_ptr<ITimeSource> m_timeSource;
+        bool m_publishClock;
+    };
+} // namespace ROS2

+ 30 - 0
Gems/ROS2/Code/Include/ROS2/Clock/ROS2TimeSource.h

@@ -0,0 +1,30 @@
+/*
+ * 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 "ITimeSource.h"
+
+namespace ROS2
+{
+    //! The ROS2TimeSource provides the time taken from the ROS 2. By default
+    //! this is system_time but it can be configured to provide the time from the other sources.
+    class ROS2TimeSource : public ITimeSource
+    {
+    public:
+        virtual ~ROS2TimeSource() = default;
+
+        // ITimeSource overrides ...
+        virtual void Activate() override {};
+        virtual void Deactivate() override {};
+
+        //! Get ROS 2 time as ROS2 message.
+        //! @see ROS2Requests::GetROSTimestamp() for more details.
+        virtual builtin_interfaces::msg::Time GetROSTimestamp() const override;
+    };
+
+} // namespace ROS2

+ 36 - 0
Gems/ROS2/Code/Include/ROS2/Clock/RealTimeSource.h

@@ -0,0 +1,36 @@
+/*
+ * 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 "ITimeSource.h"
+
+namespace ROS2
+{
+    //! The RealTimeSource starts from 0 at the start of the simulation.
+    //! This time source could be affected by the jitter in the data, simulation
+    //! computations or other similar events. On the other hand RealTimeSource
+    //! can remain consistent with the other independent clocks if it is synchronised
+    //! (e.g. through NTP).
+    class RealTimeSource : public ITimeSource
+    {
+    public:
+        virtual ~RealTimeSource() = default;
+
+        // ITimeSource overrides ...
+        virtual void Activate() override {};
+        virtual void Deactivate() override {};
+
+        //! Get simulation time as ROS 2 message.
+        //! @see ROS2Requests::GetROSTimestamp() for more details.
+        virtual builtin_interfaces::msg::Time GetROSTimestamp() const override;
+
+    private:
+        //! Get the time since start of sim, scaled with t_simulationTickScale
+        int64_t GetElapsedTimeMicroseconds() const;
+    };
+} // namespace ROS2

+ 0 - 49
Gems/ROS2/Code/Include/ROS2/Clock/SimulationClock.h

@@ -1,49 +0,0 @@
-/*
- * 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/std/chrono/chrono.h>
-#include <AzCore/std/containers/deque.h>
-#include <builtin_interfaces/msg/time.hpp>
-#include <rclcpp/publisher.hpp>
-#include <rosgraph_msgs/msg/clock.hpp>
-
-namespace ROS2
-{
-    //! Simulation clock which can tick and serve time stamps.
-    class SimulationClock
-    {
-        static constexpr size_t FramesNumberForStats = 60;
-
-    public:
-        virtual void Activate(){};
-        virtual void Deactivate(){};
-
-        //! Get simulation time as ROS2 message.
-        //! @see ROS2Requests::GetROSTimestamp() for more details.
-        virtual builtin_interfaces::msg::Time GetROSTimestamp() const;
-
-        //! Update time in the ROS 2 ecosystem.
-        //! This will publish current time to the ROS 2 `/clock` topic.
-        virtual void Tick();
-
-        //! Returns an expected loop time of simulation. It is an estimation from past frames.
-        AZStd::chrono::duration<float, AZStd::chrono::seconds::period> GetExpectedSimulationLoopTime() const;
-        virtual ~SimulationClock() = default;
-
-    private:
-        //! Get the time since start of sim, scaled with t_simulationTickScale
-        int64_t GetElapsedTimeMicroseconds() const;
-
-        AZ::s64 m_lastExecutionTime{ 0 };
-
-        rclcpp::Publisher<rosgraph_msgs::msg::Clock>::SharedPtr m_clockPublisher;
-        AZ::s64 m_currentMedian{ 0 };
-        AZStd::deque<AZ::s64> m_frameTimes;
-    };
-} // namespace ROS2

+ 43 - 0
Gems/ROS2/Code/Include/ROS2/Clock/SimulationTimeSource.h

@@ -0,0 +1,43 @@
+/*
+ * 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 "ITimeSource.h"
+#include <AzFramework/Physics/Common/PhysicsEvents.h>
+#include <AzFramework/Physics/PhysicsSystem.h>
+
+namespace ROS2
+{
+    //! The SimulationTimeSource provides timestamps calculated using updates from the physics engine.
+    //! Simulation paces the clock with stable steps, and as a result, this time source eliminates data jitter.
+    //! The simulated time can be faster or slower than the real-time, according to the configuration of the physics engine.
+    //! SimulationTimeSource is used as the default time source for the projects.
+    //! The simulated clock is incremented with delta times that were simulated by physics.
+    //! The time source registers and observes AZ::PhysicsScene and when the
+    //! simulation starts, it attaches and starts counting the updates.
+    //! It is recommended to use it with high-frequency sensors such as odometry and IMUs.
+    class SimulationTimeSource : public ITimeSource
+    {
+    public:
+        virtual ~SimulationTimeSource() = default;
+
+        // ITimeSource overrides ...
+        virtual void Activate() override;
+        virtual void Deactivate() override;
+
+        //! Get ROS 2 time as ROS2 message.
+        //! @see ROS2Requests::GetROSTimestamp() for more details.
+        virtual builtin_interfaces::msg::Time GetROSTimestamp() const override;
+
+    private:
+        double m_elapsed = 0;
+        AzPhysics::SceneEvents::OnSceneSimulationFinishHandler m_onSceneSimulationEvent;
+        AzPhysics::SystemEvents::OnSceneAddedEvent::Handler m_onSceneAdded;
+        AzPhysics::SystemEvents::OnSceneRemovedEvent::Handler m_onSceneRemoved;
+    };
+} // namespace ROS2

+ 2 - 2
Gems/ROS2/Code/Include/ROS2/ROS2Bus.h

@@ -10,7 +10,7 @@
 #include <AzCore/EBus/EBus.h>
 #include <AzCore/EBus/Event.h>
 #include <AzCore/Interface/Interface.h>
-#include <ROS2/Clock/SimulationClock.h>
+#include <ROS2/Clock/ROS2Clock.h>
 #include <builtin_interfaces/msg/time.hpp>
 #include <geometry_msgs/msg/transform_stamped.hpp>
 #include <rclcpp/node.hpp>
@@ -63,7 +63,7 @@ namespace ROS2
 
         //! Obtains a simulation clock that is used across simulation.
         //! @returns constant reference to currently running clock.
-        virtual const SimulationClock& GetSimulationClock() const = 0;
+        virtual const ROS2Clock& GetSimulationClock() const = 0;
     };
 
     class ROS2BusTraits : public AZ::EBusTraits

+ 61 - 0
Gems/ROS2/Code/Source/Clock/ROS2Clock.cpp

@@ -0,0 +1,61 @@
+/*
+ * 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 <ROS2/Clock/ROS2Clock.h>
+#include <ROS2/Clock/SimulationTimeSource.h>
+#include <ROS2/ROS2Bus.h>
+#include <rclcpp/qos.hpp>
+
+namespace ROS2
+{
+    ROS2Clock::ROS2Clock()
+        : m_timeSource(AZStd::make_unique<SimulationTimeSource>())
+        , m_publishClock(true)
+    {
+    }
+
+    ROS2Clock::ROS2Clock(AZStd::unique_ptr<ITimeSource> timeSource, bool publishClock)
+        : m_timeSource(AZStd::move(timeSource))
+        , m_publishClock(publishClock)
+    {
+    }
+
+    void ROS2Clock::Activate()
+    {
+        m_timeSource->Activate();
+    }
+
+    void ROS2Clock::Deactivate()
+    {
+        m_timeSource->Deactivate();
+    }
+
+    builtin_interfaces::msg::Time ROS2Clock::GetROSTimestamp() const
+    {
+        return m_timeSource->GetROSTimestamp();
+    }
+
+    void ROS2Clock::Tick()
+    {
+        if (!m_publishClock)
+        {
+            return;
+        }
+        if (!m_clockPublisher)
+        { // Lazy construct
+            auto ros2Node = ROS2Interface::Get()->GetNode();
+
+            rclcpp::ClockQoS qos;
+            m_clockPublisher = ros2Node->create_publisher<rosgraph_msgs::msg::Clock>("/clock", qos);
+        }
+
+        rosgraph_msgs::msg::Clock msg;
+        msg.clock = GetROSTimestamp();
+        m_clockPublisher->publish(msg);
+    }
+} // namespace ROS2

+ 20 - 0
Gems/ROS2/Code/Source/Clock/ROS2TimeSource.cpp

@@ -0,0 +1,20 @@
+/*
+ * 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 <ROS2/Clock/ROS2TimeSource.h>
+#include <ROS2/ROS2Bus.h>
+
+namespace ROS2
+{
+    builtin_interfaces::msg::Time ROS2TimeSource::GetROSTimestamp() const
+    {
+        auto ros2Node = ROS2Interface::Get()->GetNode();
+        builtin_interfaces::msg::Time timeStamp = ros2Node->get_clock()->now();
+        return timeStamp;
+    }
+} // namespace ROS2

+ 36 - 0
Gems/ROS2/Code/Source/Clock/RealTimeSource.cpp

@@ -0,0 +1,36 @@
+/*
+ * 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 <AzCore/Time/ITime.h>
+#include <ROS2/Clock/RealTimeSource.h>
+
+namespace ROS2
+{
+    builtin_interfaces::msg::Time RealTimeSource::GetROSTimestamp() const
+    {
+        const auto elapsedTime = GetElapsedTimeMicroseconds();
+
+        builtin_interfaces::msg::Time timeStamp;
+        timeStamp.sec = static_cast<int32_t>(elapsedTime / 1000000);
+        timeStamp.nanosec = static_cast<uint32_t>((elapsedTime % 1000000) * 1000);
+        return timeStamp;
+    }
+
+    int64_t RealTimeSource::GetElapsedTimeMicroseconds() const
+    {
+        if (auto* timeSystem = AZ::Interface<AZ::ITime>::Get())
+        {
+            return static_cast<int64_t>(timeSystem->GetElapsedTimeUs());
+        }
+        else
+        {
+            AZ_Error("RealTimeSource", false, "No ITime interface available for ROS2 Gem simulation clock");
+            return 0;
+        }
+    }
+} // namespace ROS2

+ 0 - 76
Gems/ROS2/Code/Source/Clock/SimulationClock.cpp

@@ -1,76 +0,0 @@
-/*
- * 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 <AzCore/Time/ITime.h>
-#include <AzCore/std/algorithm.h>
-#include <AzCore/std/containers/deque.h>
-#include <AzCore/std/containers/vector.h>
-#include <AzCore/std/sort.h>
-#include <ROS2/Clock/SimulationClock.h>
-#include <ROS2/ROS2Bus.h>
-#include <rclcpp/qos.hpp>
-
-namespace ROS2
-{
-    builtin_interfaces::msg::Time SimulationClock::GetROSTimestamp() const
-    {
-        const auto elapsedTime = GetElapsedTimeMicroseconds();
-
-        builtin_interfaces::msg::Time timeStamp;
-        timeStamp.sec = static_cast<int32_t>(elapsedTime / 1000000);
-        timeStamp.nanosec = static_cast<uint32_t>((elapsedTime % 1000000) * 1000);
-        return timeStamp;
-    }
-
-    int64_t SimulationClock::GetElapsedTimeMicroseconds() const
-    {
-        if (auto* timeSystem = AZ::Interface<AZ::ITime>::Get())
-        {
-            return static_cast<int64_t>(timeSystem->GetElapsedTimeUs());
-        }
-        else
-        {
-            AZ_Error("SimulationClock", false, "No ITime interface available for ROS2 Gem simulation clock");
-            return 0;
-        }
-    }
-
-    AZStd::chrono::duration<float, AZStd::chrono::seconds::period> SimulationClock::GetExpectedSimulationLoopTime() const
-    {
-        return AZStd::chrono::duration<AZ::s64, AZStd::chrono::microseconds::period>(m_currentMedian);
-    }
-
-    void SimulationClock::Tick()
-    {
-        auto elapsed = GetElapsedTimeMicroseconds();
-        if (!m_clockPublisher)
-        { // Lazy construct
-            auto ros2Node = ROS2Interface::Get()->GetNode();
-
-            rclcpp::ClockQoS qos;
-            m_clockPublisher = ros2Node->create_publisher<rosgraph_msgs::msg::Clock>("/clock", qos);
-        }
-
-        rosgraph_msgs::msg::Clock msg;
-        msg.clock = GetROSTimestamp();
-        m_clockPublisher->publish(msg);
-
-        AZ::s64 deltaTime = elapsed - m_lastExecutionTime;
-        m_lastExecutionTime = elapsed;
-
-        // statistics on execution time
-        m_frameTimes.push_back(deltaTime);
-        if (m_frameTimes.size() > FramesNumberForStats)
-        {
-            m_frameTimes.pop_front();
-        }
-        AZStd::vector<AZ::s64> frameTimeSorted{ m_frameTimes.begin(), m_frameTimes.end() };
-        AZStd::sort(frameTimeSorted.begin(), frameTimeSorted.end());
-        m_currentMedian = frameTimeSorted[frameTimeSorted.size() / 2];
-    }
-} // namespace ROS2

+ 4 - 6
Gems/ROS2/Code/Source/Clock/PhysicallyStableClock.cpp → Gems/ROS2/Code/Source/Clock/SimulationTimeSource.cpp

@@ -7,15 +7,13 @@
  */
 
 #include <AzCore/Time/ITime.h>
-#include <ROS2/Clock/PhysicallyStableClock.h>
-
+#include <ROS2/Clock/SimulationTimeSource.h>
 #include <ROS2/ROS2Bus.h>
-#include <rclcpp/qos.hpp>
 
 namespace ROS2
 {
 
-    void PhysicallyStableClock::Activate()
+    void SimulationTimeSource::Activate()
     {
         auto* systemInterface = AZ::Interface<AzPhysics::SystemInterface>::Get();
         if (!systemInterface)
@@ -57,12 +55,12 @@ namespace ROS2
         systemInterface->RegisterSceneRemovedEvent(m_onSceneRemoved);
     }
 
-    void PhysicallyStableClock::Deactivate()
+    void SimulationTimeSource::Deactivate()
     {
         m_onSceneSimulationEvent.Disconnect();
     };
 
-    builtin_interfaces::msg::Time PhysicallyStableClock::GetROSTimestamp() const
+    builtin_interfaces::msg::Time SimulationTimeSource::GetROSTimestamp() const
     {
         builtin_interfaces::msg::Time timeStamp;
         timeStamp.sec = static_cast<int32_t>(AZStd::floor(m_elapsed));

+ 30 - 10
Gems/ROS2/Code/Source/SystemComponents/ROS2SystemComponent.cpp

@@ -9,7 +9,9 @@
 
 #include "ROS2SystemComponent.h"
 #include <Lidar/LidarCore.h>
-#include <ROS2/Clock/PhysicallyStableClock.h>
+#include <ROS2/Clock/RealTimeSource.h>
+#include <ROS2/Clock/ROS2TimeSource.h>
+#include <ROS2/Clock/SimulationTimeSource.h>
 #include <ROS2/Communication/PublisherConfiguration.h>
 #include <ROS2/Communication/QoS.h>
 #include <ROS2/Communication/TopicConfiguration.h>
@@ -30,7 +32,8 @@
 
 namespace ROS2
 {
-    constexpr AZStd::string_view EnablePhysicsSteadyClockConfigurationKey = "/O3DE/ROS2/SteadyClock";
+    constexpr AZStd::string_view ClockTypeConfigurationKey = "/O3DE/ROS2/ClockType";
+    constexpr AZStd::string_view PublishClockConfigurationKey = "/O3DE/ROS2/PublishClock";
 
     void ROS2SystemComponent::Reflect(AZ::ReflectContext* context)
     {
@@ -113,21 +116,38 @@ namespace ROS2
 
     void ROS2SystemComponent::InitClock()
     {
-        bool useSteadyTime = false;
+        AZStd::unordered_map<AZStd::string, AZStd::function<AZStd::unique_ptr<ITimeSource>()>> clocksMap;
+        clocksMap["realtime"] = []()
+        {
+            AZ_Info("ROS2SystemComponent", "Enabling realtime clock.");
+            return AZStd::make_unique<RealTimeSource>();
+        };
+        clocksMap["simulation"] = []()
+        {
+            AZ_Info("ROS2SystemComponent", "Enabling simulation clock.");
+            return AZStd::make_unique<SimulationTimeSource>();
+        };
+        clocksMap["ros2"] = []()
+        {
+            AZ_Info("ROS2SystemComponent", "Enabling ros 2 clock.");
+            return AZStd::make_unique<ROS2TimeSource>();
+        };
+        AZStd::string clockType{ "" };
+        bool publishClock{ true };
         auto* registry = AZ::SettingsRegistry::Get();
         AZ_Assert(registry, "No Registry available");
         if (registry)
         {
-            registry->Get(useSteadyTime, EnablePhysicsSteadyClockConfigurationKey);
-            if (useSteadyTime)
+            registry->Get(publishClock, PublishClockConfigurationKey);
+            registry->Get(clockType, ClockTypeConfigurationKey);
+            if (clocksMap.contains(clockType))
             {
-                AZ_Printf("ROS2SystemComponent", "Enabling Physical steady clock");
-                m_simulationClock = AZStd::make_unique<PhysicallyStableClock>();
+                m_simulationClock = AZStd::make_unique<ROS2Clock>(clocksMap[clockType](), publishClock);
                 return;
             }
         }
-        AZ_Printf("ROS2SystemComponent", "Enabling realtime clock");
-        m_simulationClock = AZStd::make_unique<SimulationClock>();
+        AZ_Info("ROS2SystemComponent", "Cannot read registry or the clock type '%s' is unknown, enabling simulation clock.", clockType.c_str());
+        m_simulationClock = AZStd::make_unique<ROS2Clock>(clocksMap["simulation"](), publishClock);
     }
 
     void ROS2SystemComponent::Activate()
@@ -182,7 +202,7 @@ namespace ROS2
         handler.Connect(m_nodeChangedEvent);
     }
 
-    const SimulationClock& ROS2SystemComponent::GetSimulationClock() const
+    const ROS2Clock& ROS2SystemComponent::GetSimulationClock() const
     {
         return *m_simulationClock;
     }

+ 3 - 3
Gems/ROS2/Code/Source/SystemComponents/ROS2SystemComponent.h

@@ -11,7 +11,7 @@
 #include <AzCore/Component/TickBus.h>
 #include <AzCore/std/smart_ptr/unique_ptr.h>
 #include <Lidar/LidarSystem.h>
-#include <ROS2/Clock/SimulationClock.h>
+#include <ROS2/Clock/ROS2Clock.h>
 #include <ROS2/ROS2Bus.h>
 #include <builtin_interfaces/msg/time.hpp>
 #include <memory>
@@ -63,7 +63,7 @@ namespace ROS2
         void ConnectOnNodeChanged(NodeChangedEvent::Handler& handler) override;
         builtin_interfaces::msg::Time GetROSTimestamp() const override;
         void BroadcastTransform(const geometry_msgs::msg::TransformStamped& t, bool isDynamic) override;
-        const SimulationClock& GetSimulationClock() const override;
+        const ROS2Clock& GetSimulationClock() const override;
         //////////////////////////////////////////////////////////////////////////
 
     protected:
@@ -87,7 +87,7 @@ namespace ROS2
         AZStd::shared_ptr<rclcpp::executors::SingleThreadedExecutor> m_executor;
         AZStd::unique_ptr<tf2_ros::TransformBroadcaster> m_dynamicTFBroadcaster;
         AZStd::unique_ptr<tf2_ros::StaticTransformBroadcaster> m_staticTFBroadcaster;
-        AZStd::unique_ptr<SimulationClock> m_simulationClock;
+        AZStd::unique_ptr<ROS2Clock> m_simulationClock;
         NodeChangedEvent m_nodeChangedEvent;
     };
 } // namespace ROS2

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

@@ -26,8 +26,10 @@ set(FILES
         Source/Camera/PostProcessing/ROS2ImageEncodingConversionComponent.h
         Source/Camera/CameraUtilities.cpp
         Source/Camera/CameraUtilities.h
-        Source/Clock/PhysicallyStableClock.cpp
-        Source/Clock/SimulationClock.cpp
+        Source/Clock/ROS2Clock.cpp
+        Source/Clock/ROS2TimeSource.cpp
+        Source/Clock/SimulationTimeSource.cpp
+        Source/Clock/RealTimeSource.cpp
         Source/Communication/QoS.cpp
         Source/Communication/PublisherConfiguration.cpp
         Source/Communication/TopicConfiguration.cpp

+ 5 - 2
Gems/ROS2/Code/ros2_header_files.cmake

@@ -6,8 +6,11 @@
 set(FILES
         Include/ROS2/Camera/CameraCalibrationRequestBus.h
         Include/ROS2/Camera/CameraPostProcessingRequestBus.h
-        Include/ROS2/Clock/PhysicallyStableClock.h
-        Include/ROS2/Clock/SimulationClock.h
+        Include/ROS2/Clock/ROS2Clock.h
+        Include/ROS2/Clock/ITimeSource.h
+        Include/ROS2/Clock/ROS2TimeSource.h
+        Include/ROS2/Clock/SimulationTimeSource.h
+        Include/ROS2/Clock/RealTimeSource.h
         Include/ROS2/Communication/PublisherConfiguration.h
         Include/ROS2/Communication/TopicConfiguration.h
         Include/ROS2/Communication/QoS.h

+ 20 - 0
Gems/ROS2/docs/guides/ros2-gem.md

@@ -34,6 +34,11 @@ You can browse Doxygen-generated documentation on [Gem's GitHub page](https://ro
   - WheelControllerComponent
 - __Robot Import (URDF) system component__
   - ROS2RobotImporterSystemComponent
+- __Clock__
+  - ROS2Clock
+  - RealTimeSource
+  - ROS2TimeSource
+  - RealTimeSource
   
 # The Gem and ROS 2 ecosystem
 
@@ -194,6 +199,21 @@ All used services types are defined in gazebo_msgs package.
 - Detailed spawn point info access: spawn point name should be passed in request.model_name. Defined pose is sent in response.pose.
   - example call: `ros2 service call /get_spawn_point_info gazebo_msgs/srv/GetModelState '{model_name: 'spawn_spot'}'`
 
+## Clock
+You can control how simulation time is handled, which affects timestamps on all the data coming from the simulation. `ROS2Clock` class captures this behavior and publishes, or not, current time to `\clock` topic based on a configuration setting.
+To modify the clock type and enable or disable time publishing, either change configuration parameters in the `clockconfiguration.setreg` file, which is located in the `Registry` directory, or pass a parameter in the console. There are three possible settings for the sources of time:
+- realtime - runs with system time but starts at 0 when the simulation starts, effectively measuring the real time elapsed since the simulation start. If you are using the Editor, then this time source starts at 0 when the Editor starts and measures how long the Editor is open.
+- ros2 - time taken from the central simulation ROS 2 node. By default, this is system time, but can be configured otherwise through node options.
+- simulation - this is virtual time that follows a stable step and eliminates jitter from the data. It can be configured to be slower or faster than real time. This is a default clock.
+
+You can change the clock type via the `.setreg` file by changing the value of the ClockType parameter to one of the above. You can also enable or disable time publishing by changing the value of the PublishClock parameter.
+You can change the clock type via the console by adding the `--regset=` flag to the call to the simulation binary file, e.g:  
+`./build/linux_working/bin/profile/Editor --regset="/O3DE/ROS2/ClockType=realtime"`  
+You can enable or disable the time publishing in the same way, e.g:  
+`./build/linux_working/bin/profile/Editor --regset="/O3DE/ROS2/PublishClock=false"`  
+You can modify both parameters in one command, e.g:  
+`./build/linux_working/bin/profile/Editor --regset="/O3DE/ROS2/ClockType=realtime" --regset="/O3DE/ROS2/PublishClock=false`
+
 ## Handling custom ROS 2 dependencies
 
 The ROS 2 Gem will respect your choice of [__