SimulationClock.cpp 2.5 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576
  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 <AzCore/std/sort.h>
  13. #include <ROS2/Clock/SimulationClock.h>
  14. #include <ROS2/ROS2Bus.h>
  15. #include <rclcpp/qos.hpp>
  16. namespace ROS2
  17. {
  18. builtin_interfaces::msg::Time SimulationClock::GetROSTimestamp() const
  19. {
  20. const auto elapsedTime = GetElapsedTimeMicroseconds();
  21. builtin_interfaces::msg::Time timeStamp;
  22. timeStamp.sec = static_cast<int32_t>(elapsedTime / 1000000);
  23. timeStamp.nanosec = static_cast<uint32_t>((elapsedTime % 1000000) * 1000);
  24. return timeStamp;
  25. }
  26. int64_t SimulationClock::GetElapsedTimeMicroseconds() const
  27. {
  28. if (auto* timeSystem = AZ::Interface<AZ::ITime>::Get())
  29. {
  30. return static_cast<int64_t>(timeSystem->GetElapsedTimeUs());
  31. }
  32. else
  33. {
  34. AZ_Error("SimulationClock", false, "No ITime interface available for ROS2 Gem simulation clock");
  35. return 0;
  36. }
  37. }
  38. AZStd::chrono::duration<float, AZStd::chrono::seconds::period> SimulationClock::GetExpectedSimulationLoopTime() const
  39. {
  40. return AZStd::chrono::duration<AZ::s64, AZStd::chrono::microseconds::period>(m_currentMedian);
  41. }
  42. void SimulationClock::Tick()
  43. {
  44. auto elapsed = GetElapsedTimeMicroseconds();
  45. if (!m_clockPublisher)
  46. { // Lazy construct
  47. auto ros2Node = ROS2Interface::Get()->GetNode();
  48. rclcpp::ClockQoS qos;
  49. m_clockPublisher = ros2Node->create_publisher<rosgraph_msgs::msg::Clock>("/clock", qos);
  50. }
  51. rosgraph_msgs::msg::Clock msg;
  52. msg.clock = GetROSTimestamp();
  53. m_clockPublisher->publish(msg);
  54. AZ::s64 deltaTime = elapsed - m_lastExecutionTime;
  55. m_lastExecutionTime = elapsed;
  56. // statistics on execution time
  57. m_frameTimes.push_back(deltaTime);
  58. if (m_frameTimes.size() > FramesNumberForStats)
  59. {
  60. m_frameTimes.pop_front();
  61. }
  62. AZStd::vector<AZ::s64> frameTimeSorted{ m_frameTimes.begin(), m_frameTimes.end() };
  63. AZStd::sort(frameTimeSorted.begin(), frameTimeSorted.end());
  64. m_currentMedian = frameTimeSorted[frameTimeSorted.size() / 2];
  65. }
  66. } // namespace ROS2