ROS2SystemComponent.cpp 8.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250
  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 <signal.h>
  9. #include "ROS2SystemComponent.h"
  10. #include <ROS2/Clock/ROS2TimeSource.h>
  11. #include <ROS2/Clock/RealTimeSource.h>
  12. #include <ROS2/Clock/SimulationTimeSource.h>
  13. #include <ROS2/Communication/PublisherConfiguration.h>
  14. #include <ROS2/Communication/QoS.h>
  15. #include <ROS2/Communication/TopicConfiguration.h>
  16. #include <ROS2/Utilities/ROS2Conversions.h>
  17. #include <AzCore/Serialization/EditContext.h>
  18. #include <AzCore/Serialization/EditContextConstants.inl>
  19. #include <AzCore/Serialization/SerializeContext.h>
  20. #include <AzCore/Settings/SettingsRegistry.h>
  21. #include <AzCore/Time/ITime.h>
  22. #include <AzCore/std/smart_ptr/make_shared.h>
  23. #include <AzCore/std/sort.h>
  24. #include <AzCore/std/string/string_view.h>
  25. #include <AzFramework/API/ApplicationAPI.h>
  26. namespace ROS2
  27. {
  28. constexpr AZStd::string_view ClockTypeConfigurationKey = "/O3DE/ROS2/ClockType";
  29. constexpr AZStd::string_view PublishClockConfigurationKey = "/O3DE/ROS2/PublishClock";
  30. constexpr size_t FramesNumberForStats = 60;
  31. void ROS2SystemComponent::Reflect(AZ::ReflectContext* context)
  32. {
  33. // Reflect structs not strictly owned by any single component
  34. QoS::Reflect(context);
  35. TopicConfiguration::Reflect(context);
  36. PublisherConfiguration::Reflect(context);
  37. if (AZ::SerializeContext* serialize = azrtti_cast<AZ::SerializeContext*>(context))
  38. {
  39. serialize->Class<ROS2SystemComponent, AZ::Component>()->Version(0);
  40. if (AZ::EditContext* ec = serialize->GetEditContext())
  41. {
  42. ec->Class<ROS2SystemComponent>(
  43. "ROS 2 System Component",
  44. "This component is responsible for creating ROS 2 node and executor, provides ROS 2 interfaces, manages ROS 2 clock "
  45. "and publishes transforms.")
  46. ->ClassElement(AZ::Edit::ClassElements::EditorData, "")
  47. ->Attribute(AZ::Edit::Attributes::AppearsInAddComponentMenu, AZ_CRC_CE("System"))
  48. ->Attribute(AZ::Edit::Attributes::Category, "ROS2")
  49. ->Attribute(AZ::Edit::Attributes::AutoExpand, true);
  50. }
  51. }
  52. }
  53. void ROS2SystemComponent::GetProvidedServices(AZ::ComponentDescriptor::DependencyArrayType& provided)
  54. {
  55. provided.push_back(AZ_CRC_CE("ROS2Service"));
  56. }
  57. void ROS2SystemComponent::GetIncompatibleServices(AZ::ComponentDescriptor::DependencyArrayType& incompatible)
  58. {
  59. incompatible.push_back(AZ_CRC_CE("ROS2Service"));
  60. }
  61. void ROS2SystemComponent::GetRequiredServices([[maybe_unused]] AZ::ComponentDescriptor::DependencyArrayType& required)
  62. {
  63. required.push_back(AZ_CRC("AssetDatabaseService", 0x3abf5601));
  64. required.push_back(AZ_CRC("RPISystem", 0xf2add773));
  65. }
  66. void ROS2SystemComponent::GetDependentServices([[maybe_unused]] AZ::ComponentDescriptor::DependencyArrayType& dependent)
  67. {
  68. }
  69. ROS2SystemComponent::ROS2SystemComponent()
  70. {
  71. if (ROS2Interface::Get() == nullptr)
  72. {
  73. ROS2Interface::Register(this);
  74. }
  75. }
  76. ROS2SystemComponent::~ROS2SystemComponent()
  77. {
  78. if (ROS2Interface::Get() == this)
  79. {
  80. ROS2Interface::Unregister(this);
  81. }
  82. rclcpp::shutdown();
  83. }
  84. void ROS2SystemComponent::Init()
  85. {
  86. rclcpp::init(0, 0);
  87. // handle signals, e.g. via `Ctrl+C` hotkey or `kill` command
  88. auto handler = [](int sig)
  89. {
  90. rclcpp::shutdown(); // shutdown rclcpp
  91. std::raise(sig); // shutdown o3de
  92. };
  93. signal(SIGINT, handler);
  94. signal(SIGTERM, handler);
  95. }
  96. void ROS2SystemComponent::InitClock()
  97. {
  98. AZStd::unordered_map<AZStd::string, AZStd::function<AZStd::unique_ptr<ITimeSource>()>> clocksMap;
  99. clocksMap["realtime"] = []()
  100. {
  101. AZ_Info("ROS2SystemComponent", "Enabling realtime clock.");
  102. return AZStd::make_unique<RealTimeSource>();
  103. };
  104. clocksMap["simulation"] = []()
  105. {
  106. AZ_Info("ROS2SystemComponent", "Enabling simulation clock.");
  107. return AZStd::make_unique<SimulationTimeSource>();
  108. };
  109. clocksMap["ros2"] = []()
  110. {
  111. AZ_Info("ROS2SystemComponent", "Enabling ros 2 clock.");
  112. return AZStd::make_unique<ROS2TimeSource>();
  113. };
  114. AZStd::string clockType{ "" };
  115. bool publishClock{ true };
  116. auto* registry = AZ::SettingsRegistry::Get();
  117. AZ_Assert(registry, "No Registry available");
  118. if (registry)
  119. {
  120. registry->Get(publishClock, PublishClockConfigurationKey);
  121. registry->Get(clockType, ClockTypeConfigurationKey);
  122. if (clocksMap.contains(clockType))
  123. {
  124. m_simulationClock = AZStd::make_unique<ROS2Clock>(clocksMap[clockType](), publishClock);
  125. return;
  126. }
  127. }
  128. AZ_Info(
  129. "ROS2SystemComponent", "Cannot read registry or the clock type '%s' is unknown, enabling simulation clock.", clockType.c_str());
  130. m_simulationClock = AZStd::make_unique<ROS2Clock>(clocksMap["simulation"](), publishClock);
  131. }
  132. void ROS2SystemComponent::Activate()
  133. {
  134. InitClock();
  135. m_simulationClock->Activate();
  136. m_ros2Node = std::make_shared<rclcpp::Node>("o3de_ros2_node");
  137. m_executor = AZStd::make_shared<rclcpp::executors::SingleThreadedExecutor>();
  138. m_executor->add_node(m_ros2Node);
  139. m_staticTFBroadcaster = AZStd::make_unique<tf2_ros::StaticTransformBroadcaster>(m_ros2Node);
  140. m_dynamicTFBroadcaster = AZStd::make_unique<tf2_ros::TransformBroadcaster>(m_ros2Node);
  141. ROS2RequestBus::Handler::BusConnect();
  142. AZ::TickBus::Handler::BusConnect();
  143. m_nodeChangedEvent.Signal(m_ros2Node);
  144. }
  145. void ROS2SystemComponent::Deactivate()
  146. {
  147. AZ::TickBus::Handler::BusDisconnect();
  148. ROS2RequestBus::Handler::BusDisconnect();
  149. if (m_simulationClock)
  150. {
  151. m_simulationClock->Deactivate();
  152. }
  153. m_dynamicTFBroadcaster.reset();
  154. m_staticTFBroadcaster.reset();
  155. if (m_executor)
  156. {
  157. if (m_ros2Node)
  158. {
  159. m_executor->remove_node(m_ros2Node);
  160. }
  161. m_executor.reset();
  162. }
  163. m_simulationClock.reset();
  164. m_ros2Node.reset();
  165. m_nodeChangedEvent.Signal(m_ros2Node);
  166. }
  167. builtin_interfaces::msg::Time ROS2SystemComponent::GetROSTimestamp() const
  168. {
  169. return m_simulationClock->GetROSTimestamp();
  170. }
  171. std::shared_ptr<rclcpp::Node> ROS2SystemComponent::GetNode() const
  172. {
  173. return m_ros2Node;
  174. }
  175. void ROS2SystemComponent::ConnectOnNodeChanged(NodeChangedEvent::Handler& handler)
  176. {
  177. handler.Connect(m_nodeChangedEvent);
  178. }
  179. const ROS2Clock& ROS2SystemComponent::GetSimulationClock() const
  180. {
  181. return *m_simulationClock;
  182. }
  183. void ROS2SystemComponent::BroadcastTransform(const geometry_msgs::msg::TransformStamped& t, bool isDynamic)
  184. {
  185. if (isDynamic)
  186. {
  187. m_frameTransforms.push_back(t);
  188. }
  189. else
  190. {
  191. m_staticTFBroadcaster->sendTransform(t);
  192. }
  193. }
  194. void ROS2SystemComponent::OnTick([[maybe_unused]] float deltaTime, [[maybe_unused]] AZ::ScriptTimePoint time)
  195. {
  196. if (rclcpp::ok())
  197. {
  198. m_dynamicTFBroadcaster->sendTransform(m_frameTransforms);
  199. m_frameTransforms.clear();
  200. m_simulationClock->Tick();
  201. m_executor->spin_some();
  202. }
  203. // Calculate simulation loop time
  204. const auto simulationTimestamp = m_simulationClock->GetROSTimestamp();
  205. const float deltaSimTime = ROS2Conversions::GetTimeDifference(m_lastSimulationTime, simulationTimestamp);
  206. // Filter out the outliers
  207. m_simulationLoopTimes.push_back(deltaSimTime);
  208. if (m_simulationLoopTimes.size() > FramesNumberForStats)
  209. {
  210. m_simulationLoopTimes.pop_front();
  211. }
  212. AZStd::vector<float> frameTimeSorted{ m_simulationLoopTimes.begin(), m_simulationLoopTimes.end() };
  213. AZStd::sort(frameTimeSorted.begin(), frameTimeSorted.end());
  214. m_simulationLoopTimeMedian = frameTimeSorted[frameTimeSorted.size() / 2];
  215. m_lastSimulationTime = simulationTimestamp;
  216. }
  217. float ROS2SystemComponent::GetExpectedSimulationLoopTime() const
  218. {
  219. return m_simulationLoopTimeMedian;
  220. }
  221. } // namespace ROS2