SimulationClock.cpp 2.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475
  1. /*
  2. * Copyright (c) Contributors to the Open 3D Engine Project.
  3. * For complete copyright and license terms please see the LICENSE at the root of this distribution.
  4. *
  5. * SPDX-License-Identifier: Apache-2.0 OR MIT
  6. *
  7. */
  8. #include <AzCore/Time/ITime.h>
  9. #include <AzCore/std/algorithm.h>
  10. #include <AzCore/std/containers/deque.h>
  11. #include <AzCore/std/containers/vector.h>
  12. #include <ROS2/Clock/SimulationClock.h>
  13. #include <ROS2/ROS2Bus.h>
  14. #include <rclcpp/qos.hpp>
  15. namespace ROS2
  16. {
  17. builtin_interfaces::msg::Time SimulationClock::GetROSTimestamp() const
  18. {
  19. const auto elapsedTime = GetElapsedTimeMicroseconds();
  20. builtin_interfaces::msg::Time timeStamp;
  21. timeStamp.sec = static_cast<int32_t>(elapsedTime / 1000000);
  22. timeStamp.nanosec = static_cast<uint32_t>((elapsedTime % 1000000) * 1000);
  23. return timeStamp;
  24. }
  25. int64_t SimulationClock::GetElapsedTimeMicroseconds() const
  26. {
  27. if (auto* timeSystem = AZ::Interface<AZ::ITime>::Get())
  28. {
  29. return static_cast<int64_t>(timeSystem->GetElapsedTimeUs());
  30. }
  31. else
  32. {
  33. AZ_Error("SimulationClock", false, "No ITime interface available for ROS2 Gem simulation clock");
  34. return 0;
  35. }
  36. }
  37. AZStd::chrono::duration<float, AZStd::chrono::seconds::period> SimulationClock::GetExpectedSimulationLoopTime() const
  38. {
  39. return AZStd::chrono::duration<AZ::s64, AZStd::chrono::microseconds::period>(m_currentMedian);
  40. }
  41. void SimulationClock::Tick()
  42. {
  43. auto elapsed = GetElapsedTimeMicroseconds();
  44. if (!m_clockPublisher)
  45. { // Lazy construct
  46. auto ros2Node = ROS2Interface::Get()->GetNode();
  47. rclcpp::ClockQoS qos;
  48. m_clockPublisher = ros2Node->create_publisher<rosgraph_msgs::msg::Clock>("/clock", qos);
  49. }
  50. rosgraph_msgs::msg::Clock msg;
  51. msg.clock = GetROSTimestamp();
  52. m_clockPublisher->publish(msg);
  53. AZ::s64 deltaTime = elapsed - m_lastExecutionTime;
  54. m_lastExecutionTime = elapsed;
  55. // statistics on execution time
  56. m_frameTimes.push_back(deltaTime);
  57. if (m_frameTimes.size() > FramesNumberForStats)
  58. {
  59. m_frameTimes.pop_front();
  60. }
  61. AZStd::vector<AZ::s64> frameTimeSorted{ m_frameTimes.begin(), m_frameTimes.end() };
  62. AZStd::sort(frameTimeSorted.begin(), frameTimeSorted.end());
  63. m_currentMedian = frameTimeSorted[frameTimeSorted.size() / 2];
  64. }
  65. } // namespace ROS2