Skip to content

Commit 6c61b49

Browse files
Added simple API to listen for ros2 system component state change (o3de#599)
Signed-off-by: Mateusz Wasilewski <[email protected]>
1 parent 3eb51b8 commit 6c61b49

File tree

3 files changed

+19
-2
lines changed

3 files changed

+19
-2
lines changed

Gems/ROS2/Code/Include/ROS2/ROS2Bus.h

Lines changed: 10 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -8,10 +8,11 @@
88
#pragma once
99

1010
#include <AzCore/EBus/EBus.h>
11+
#include <AzCore/EBus/Event.h>
1112
#include <AzCore/Interface/Interface.h>
13+
#include <ROS2/Clock/SimulationClock.h>
1214
#include <builtin_interfaces/msg/time.hpp>
1315
#include <geometry_msgs/msg/transform_stamped.hpp>
14-
#include <ROS2/Clock/SimulationClock.h>
1516
#include <rclcpp/node.hpp>
1617

1718
namespace ROS2
@@ -24,6 +25,8 @@ namespace ROS2
2425
class ROS2Requests
2526
{
2627
public:
28+
using NodeChangedEvent = AZ::Event<std::shared_ptr<rclcpp::Node>>;
29+
2730
AZ_RTTI(ROS2Requests, "{a9bdbff6-e644-430d-8096-cdb53c88e8fc}");
2831
virtual ~ROS2Requests() = default;
2932

@@ -33,6 +36,12 @@ namespace ROS2
3336
//! @note Alternatively, you can use your own node along with an executor.
3437
virtual std::shared_ptr<rclcpp::Node> GetNode() const = 0;
3538

39+
//! Attach handler to ROS2 node change events.
40+
//! You can use this method to correctly initialize SystemComponents that depend on ROS2Node.
41+
//! @param handler which will be connected to NodeChangedEvent.
42+
//! @note callback is active as long as handler is not destroyed.
43+
virtual void ConnectOnNodeChanged(NodeChangedEvent::Handler& handler) = 0;
44+
3645
//! Acquire current time as ROS2 timestamp.
3746
//! Timestamps provide temporal context for messages such as sensor data.
3847
//! @code
@@ -55,7 +64,6 @@ namespace ROS2
5564
//! Obtains a simulation clock that is used across simulation.
5665
//! @returns constant reference to currently running clock.
5766
virtual const SimulationClock& GetSimulationClock() const = 0;
58-
5967
};
6068

6169
class ROS2BusTraits : public AZ::EBusTraits

Gems/ROS2/Code/Source/ROS2SystemComponent.cpp

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -151,6 +151,7 @@ namespace ROS2
151151

152152
ROS2RequestBus::Handler::BusConnect();
153153
AZ::TickBus::Handler::BusConnect();
154+
m_nodeChangedEvent.Signal(m_ros2Node);
154155
}
155156

156157
void ROS2SystemComponent::Deactivate()
@@ -165,6 +166,7 @@ namespace ROS2
165166
m_executor.reset();
166167
m_simulationClock.reset();
167168
m_ros2Node.reset();
169+
m_nodeChangedEvent.Signal(m_ros2Node);
168170
}
169171

170172
builtin_interfaces::msg::Time ROS2SystemComponent::GetROSTimestamp() const
@@ -177,6 +179,11 @@ namespace ROS2
177179
return m_ros2Node;
178180
}
179181

182+
void ROS2SystemComponent::ConnectOnNodeChanged(NodeChangedEvent::Handler& handler)
183+
{
184+
handler.Connect(m_nodeChangedEvent);
185+
}
186+
180187
const SimulationClock& ROS2SystemComponent::GetSimulationClock() const
181188
{
182189
return *m_simulationClock;

Gems/ROS2/Code/Source/ROS2SystemComponent.h

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -61,6 +61,7 @@ namespace ROS2
6161
//////////////////////////////////////////////////////////////////////////
6262
// ROS2RequestBus::Handler overrides
6363
std::shared_ptr<rclcpp::Node> GetNode() const override;
64+
void ConnectOnNodeChanged(NodeChangedEvent::Handler& handler) override;
6465
builtin_interfaces::msg::Time GetROSTimestamp() const override;
6566
void BroadcastTransform(const geometry_msgs::msg::TransformStamped& t, bool isDynamic) override;
6667
const SimulationClock& GetSimulationClock() const override;
@@ -90,6 +91,7 @@ namespace ROS2
9091
AZStd::unique_ptr<tf2_ros::TransformBroadcaster> m_dynamicTFBroadcaster;
9192
AZStd::unique_ptr<tf2_ros::StaticTransformBroadcaster> m_staticTFBroadcaster;
9293
AZStd::unique_ptr<SimulationClock> m_simulationClock;
94+
NodeChangedEvent m_nodeChangedEvent;
9395
//! Load the pass templates of the ROS2 gem.
9496
void LoadPassTemplateMappings();
9597
AZ::RPI::PassSystemInterface::OnReadyLoadTemplatesEvent::Handler m_loadTemplatesHandler;

0 commit comments

Comments
 (0)