File tree Expand file tree Collapse file tree 3 files changed +9
-4
lines changed Expand file tree Collapse file tree 3 files changed +9
-4
lines changed Original file line number Diff line number Diff line change @@ -50,7 +50,7 @@ namespace ROS2
50
50
// ! only once and are to be used when the spatial relationship between two frames does not change.
51
51
// ! @note Transforms are already published by each ROS2FrameComponent.
52
52
// ! 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;
54
54
55
55
// ! Obtains a simulation clock that is used across simulation.
56
56
// ! @returns constant reference to currently running clock.
Original file line number Diff line number Diff line change @@ -182,11 +182,11 @@ namespace ROS2
182
182
return *m_simulationClock;
183
183
}
184
184
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)
186
186
{
187
187
if (isDynamic)
188
188
{
189
- m_dynamicTFBroadcaster-> sendTransform (t);
189
+ m_frameTransforms. push_back (t);
190
190
}
191
191
else
192
192
{
@@ -198,6 +198,9 @@ namespace ROS2
198
198
{
199
199
if (rclcpp::ok ())
200
200
{
201
+ m_dynamicTFBroadcaster->sendTransform (m_frameTransforms);
202
+ m_frameTransforms.clear ();
203
+
201
204
m_simulationClock->Tick ();
202
205
m_executor->spin_some ();
203
206
}
Original file line number Diff line number Diff line change @@ -62,7 +62,7 @@ namespace ROS2
62
62
// ROS2RequestBus::Handler overrides
63
63
std::shared_ptr<rclcpp::Node> GetNode () const override ;
64
64
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 ;
66
66
const SimulationClock& GetSimulationClock () const override ;
67
67
// ////////////////////////////////////////////////////////////////////////
68
68
@@ -83,6 +83,8 @@ namespace ROS2
83
83
private:
84
84
void InitClock ();
85
85
86
+ std::vector<geometry_msgs::msg::TransformStamped> m_frameTransforms;
87
+
86
88
std::shared_ptr<rclcpp::Node> m_ros2Node;
87
89
AZStd::shared_ptr<rclcpp::executors::SingleThreadedExecutor> m_executor;
88
90
AZStd::unique_ptr<tf2_ros::TransformBroadcaster> m_dynamicTFBroadcaster;
You can’t perform that action at this time.
0 commit comments