#include <ROS2Bus.h>
Inherited by ROS2::ROS2SystemComponent [protected].
|  | 
| using | NodeChangedEvent = AZ::Event< std::shared_ptr< rclcpp::Node > > | 
|  | 
Interface to the central ROS2SystemComponent. Use this API through ROS2Interface, for example: 
auto node = ROS2Interface::Get()->GetNode();
◆ BroadcastTransform()
  
  | 
        
          | virtual void ROS2::ROS2Requests::BroadcastTransform | ( | const geometry_msgs::msg::TransformStamped & | t, |  
          |  |  | bool | isDynamic |  
          |  | ) |  |  |  | pure virtual | 
 
Send transformation between ROS2 frames. 
- Parameters
- 
  
    | t | is a ROS2 TransformStamped message. |  | isDynamic | controls 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
- 
  
    | handler | which 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:
- Gems/ROS2/Code/Include/ROS2/ROS2Bus.h