ROS2Bus.h 3.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384
  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. #pragma once
  9. #include <AzCore/EBus/EBus.h>
  10. #include <AzCore/EBus/Event.h>
  11. #include <AzCore/Interface/Interface.h>
  12. #include <ROS2/Clock/ROS2Clock.h>
  13. #include <builtin_interfaces/msg/time.hpp>
  14. #include <geometry_msgs/msg/transform_stamped.hpp>
  15. #include <rclcpp/node.hpp>
  16. namespace ROS2
  17. {
  18. //! Interface to the central ROS2SystemComponent.
  19. //! Use this API through ROS2Interface, for example:
  20. //! @code
  21. //! auto node = ROS2Interface::Get()->GetNode();
  22. //! @endcode
  23. class ROS2Requests
  24. {
  25. public:
  26. using NodeChangedEvent = AZ::Event<std::shared_ptr<rclcpp::Node>>;
  27. AZ_RTTI(ROS2Requests, "{a9bdbff6-e644-430d-8096-cdb53c88e8fc}");
  28. virtual ~ROS2Requests() = default;
  29. //! Get a central ROS2 node of the Gem.
  30. //! You can use this node to create publishers and subscribers.
  31. //! @return The central ROS2 node which holds default publishers for core topics such as /clock and /tf.
  32. //! @note Alternatively, you can use your own node along with an executor.
  33. virtual std::shared_ptr<rclcpp::Node> GetNode() const = 0;
  34. //! Attach handler to ROS2 node change events.
  35. //! You can use this method to correctly initialize SystemComponents that depend on ROS2Node.
  36. //! @param handler which will be connected to NodeChangedEvent.
  37. //! @note callback is active as long as handler is not destroyed.
  38. virtual void ConnectOnNodeChanged(NodeChangedEvent::Handler& handler) = 0;
  39. //! Acquire current time as ROS2 timestamp.
  40. //! Timestamps provide temporal context for messages such as sensor data.
  41. //! @code
  42. //! auto message = sensor_msgs::msg::PointCloud2();
  43. //! message.header.stamp = ROS2Interface::Get()->GetROSTimestamp();
  44. //! @endcode
  45. //! @return Simulation time in ROS2 format. Time source is also valid with non-real time settings.
  46. //! @note Make sure to set the use_sim_time parameter for ROS2 nodes which will use the simulation data.
  47. virtual builtin_interfaces::msg::Time GetROSTimestamp() const = 0;
  48. //! Send transformation between ROS2 frames.
  49. //! @param t is a <a href="https://docs.ros2.org/latest/api/geometry_msgs/msg/TransformStamped.html">ROS2 TransformStamped
  50. //! message</a>.
  51. //! @param isDynamic controls whether a static or dynamic transform is sent. Static transforms are published
  52. //! only once and are to be used when the spatial relationship between two frames does not change.
  53. //! @note Transforms are already published by each ROS2FrameComponent.
  54. //! Use this function directly only when default behavior of ROS2FrameComponent is not sufficient.
  55. virtual void BroadcastTransform(const geometry_msgs::msg::TransformStamped& t, bool isDynamic) = 0;
  56. //! Obtains a simulation clock that is used across simulation.
  57. //! @returns constant reference to currently running clock.
  58. virtual const ROS2Clock& GetSimulationClock() const = 0;
  59. //! Returns an expected loop time of simulation. It is an estimation from past frames.
  60. virtual float GetExpectedSimulationLoopTime() const = 0;
  61. };
  62. class ROS2BusTraits : public AZ::EBusTraits
  63. {
  64. public:
  65. //////////////////////////////////////////////////////////////////////////
  66. // EBusTraits overrides
  67. static constexpr AZ::EBusHandlerPolicy HandlerPolicy = AZ::EBusHandlerPolicy::Single;
  68. static constexpr AZ::EBusAddressPolicy AddressPolicy = AZ::EBusAddressPolicy::Single;
  69. //////////////////////////////////////////////////////////////////////////
  70. };
  71. using ROS2RequestBus = AZ::EBus<ROS2Requests, ROS2BusTraits>;
  72. using ROS2Interface = AZ::Interface<ROS2Requests>;
  73. } // namespace ROS2