Skip to content

Commit 281b15e

Browse files
authored
Broadcast transforms en masse (o3de#584)
Signed-off-by: Adam Dabrowski <[email protected]>
1 parent 6f65652 commit 281b15e

File tree

3 files changed

+9
-4
lines changed

3 files changed

+9
-4
lines changed

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

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -50,7 +50,7 @@ namespace ROS2
5050
//! only once and are to be used when the spatial relationship between two frames does not change.
5151
//! @note Transforms are already published by each ROS2FrameComponent.
5252
//! Use this function directly only when default behavior of ROS2FrameComponent is not sufficient.
53-
virtual void BroadcastTransform(const geometry_msgs::msg::TransformStamped& t, bool isDynamic) const = 0;
53+
virtual void BroadcastTransform(const geometry_msgs::msg::TransformStamped& t, bool isDynamic) = 0;
5454

5555
//! Obtains a simulation clock that is used across simulation.
5656
//! @returns constant reference to currently running clock.

Gems/ROS2/Code/Source/ROS2SystemComponent.cpp

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -182,11 +182,11 @@ namespace ROS2
182182
return *m_simulationClock;
183183
}
184184

185-
void ROS2SystemComponent::BroadcastTransform(const geometry_msgs::msg::TransformStamped& t, bool isDynamic) const
185+
void ROS2SystemComponent::BroadcastTransform(const geometry_msgs::msg::TransformStamped& t, bool isDynamic)
186186
{
187187
if (isDynamic)
188188
{
189-
m_dynamicTFBroadcaster->sendTransform(t);
189+
m_frameTransforms.push_back(t);
190190
}
191191
else
192192
{
@@ -198,6 +198,9 @@ namespace ROS2
198198
{
199199
if (rclcpp::ok())
200200
{
201+
m_dynamicTFBroadcaster->sendTransform(m_frameTransforms);
202+
m_frameTransforms.clear();
203+
201204
m_simulationClock->Tick();
202205
m_executor->spin_some();
203206
}

Gems/ROS2/Code/Source/ROS2SystemComponent.h

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -62,7 +62,7 @@ namespace ROS2
6262
// ROS2RequestBus::Handler overrides
6363
std::shared_ptr<rclcpp::Node> GetNode() const override;
6464
builtin_interfaces::msg::Time GetROSTimestamp() const override;
65-
void BroadcastTransform(const geometry_msgs::msg::TransformStamped& t, bool isDynamic) const override;
65+
void BroadcastTransform(const geometry_msgs::msg::TransformStamped& t, bool isDynamic) override;
6666
const SimulationClock& GetSimulationClock() const override;
6767
//////////////////////////////////////////////////////////////////////////
6868

@@ -83,6 +83,8 @@ namespace ROS2
8383
private:
8484
void InitClock();
8585

86+
std::vector<geometry_msgs::msg::TransformStamped> m_frameTransforms;
87+
8688
std::shared_ptr<rclcpp::Node> m_ros2Node;
8789
AZStd::shared_ptr<rclcpp::executors::SingleThreadedExecutor> m_executor;
8890
AZStd::unique_ptr<tf2_ros::TransformBroadcaster> m_dynamicTFBroadcaster;

0 commit comments

Comments
 (0)