Open 3D Engine ROS2 Gem API Reference 25.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>

Inherited by ROS2::ROS2SystemComponent [protected].

Public Types

using NodeChangedEvent = AZ::Event< std::shared_ptr< rclcpp::Node > >
 

Public Member Functions

 AZ_RTTI (ROS2Requests, ROS2RequestsTypeId)
 
virtual std::shared_ptr< rclcpp::Node > GetNode () const =0
 
virtual void ConnectOnNodeChanged (NodeChangedEvent::Handler &handler)=0
 
virtual void BroadcastTransform (const geometry_msgs::msg::TransformStamped &t, bool isDynamic)=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 
)
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.

Implemented in ROS2::ROS2SystemComponent.

◆ ConnectOnNodeChanged()

virtual void ROS2::ROS2Requests::ConnectOnNodeChanged ( NodeChangedEvent::Handler &  handler)
pure virtual

Attach handler to ROS2 node change events. You can use this method to correctly initialize SystemComponents that depend on ROS2Node.

Parameters
handlerwhich will be connected to NodeChangedEvent.
Note
callback is active as long as handler is not destroyed.

Implemented in ROS2::ROS2SystemComponent.

◆ 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.

Implemented in ROS2::ROS2SystemComponent.


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