Open 3D Engine ROS2 Gem API Reference 23.10.0
O3DE is an open-source, fully-featured, high-fidelity, modular 3D engine for building games and simulations, available to every industry.
ROS2::ROS2Requests Class Referenceabstract

#include <ROS2Bus.h>

Public Member Functions

 AZ_RTTI (ROS2Requests, "{a9bdbff6-e644-430d-8096-cdb53c88e8fc}")
 
virtual std::shared_ptr< rclcpp::Node > GetNode () const =0
 
virtual builtin_interfaces::msg::Time GetROSTimestamp () const =0
 
virtual void BroadcastTransform (const geometry_msgs::msg::TransformStamped &t, bool isDynamic) const =0
 
virtual const SimulationClockGetSimulationClock () const =0
 

Detailed Description

Interface to the central ROS2SystemComponent. Use this API through ROS2Interface, for example:

auto node = ROS2Interface::Get()->GetNode();

Member Function Documentation

◆ BroadcastTransform()

virtual void ROS2::ROS2Requests::BroadcastTransform ( const geometry_msgs::msg::TransformStamped &  t,
bool  isDynamic 
) const
pure virtual

Send transformation between ROS2 frames.

Parameters
tis a ROS2 TransformStamped message.
isDynamiccontrols whether a static or dynamic transform is sent. Static transforms are published only once and are to be used when the spatial relationship between two frames does not change.
Note
Transforms are already published by each ROS2FrameComponent. Use this function directly only when default behavior of ROS2FrameComponent is not sufficient.

◆ GetNode()

virtual std::shared_ptr< rclcpp::Node > ROS2::ROS2Requests::GetNode ( ) const
pure virtual

Get a central ROS2 node of the Gem. You can use this node to create publishers and subscribers.

Returns
The central ROS2 node which holds default publishers for core topics such as /clock and /tf.
Note
Alternatively, you can use your own node along with an executor.

◆ GetROSTimestamp()

virtual builtin_interfaces::msg::Time ROS2::ROS2Requests::GetROSTimestamp ( ) const
pure virtual

Acquire current time as ROS2 timestamp. Timestamps provide temporal context for messages such as sensor data.

auto message = sensor_msgs::msg::PointCloud2();
message.header.stamp = ROS2Interface::Get()->GetROSTimestamp();
Returns
Simulation time in ROS2 format. Time source is also valid with non-real time settings.
Note
Make sure to set the use_sim_time parameter for ROS2 nodes which will use the simulation data.

◆ GetSimulationClock()

virtual const SimulationClock & ROS2::ROS2Requests::GetSimulationClock ( ) const
pure virtual

Obtains a simulation clock that is used across simulation.

Returns
constant reference to currently running clock.

The documentation for this class was generated from the following file: