Skip to content

Commit 9ed832e

Browse files
Migrate TransformBroadcaster usage to use shared ptr. (#5569)
Signed-off-by: Leander Stephen D'Souza <[email protected]>
1 parent a25b67e commit 9ed832e

File tree

2 files changed

+4
-4
lines changed

2 files changed

+4
-4
lines changed

nav2_route/test/test_goal_intent_extractor.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -83,7 +83,7 @@ TEST(GoalIntentExtractorTest, test_transform_pose)
8383
node->get_node_timers_interface());
8484
tf->setCreateTimerInterface(timer_interface);
8585
auto transform_listener = std::make_shared<tf2_ros::TransformListener>(*tf);
86-
tf2_ros::TransformBroadcaster broadcaster(node);
86+
auto broadcaster = std::make_shared<tf2_ros::TransformBroadcaster>(node);
8787
std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber = nullptr;
8888
extractor.configure(node, graph, &id_map, tf, costmap_subscriber, "map", "base_link");
8989

@@ -101,7 +101,7 @@ TEST(GoalIntentExtractorTest, test_transform_pose)
101101
transform.header.frame_id = "map";
102102
transform.header.stamp = node->now();
103103
transform.child_frame_id = "gps";
104-
broadcaster.sendTransform(transform);
104+
broadcaster->sendTransform(transform);
105105
EXPECT_NO_THROW(extractor.transformPose(pose, "map"));
106106
}
107107

nav2_route/test/test_route_tracker.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -69,7 +69,7 @@ TEST(RouteTrackerTest, test_get_robot_pose)
6969
node->get_node_timers_interface());
7070
tf->setCreateTimerInterface(timer_interface);
7171
auto transform_listener = std::make_shared<tf2_ros::TransformListener>(*tf);
72-
tf2_ros::TransformBroadcaster broadcaster(node);
72+
auto broadcaster = std::make_shared<tf2_ros::TransformBroadcaster>(node);
7373
std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber;
7474

7575
RouteTracker tracker;
@@ -81,7 +81,7 @@ TEST(RouteTrackerTest, test_get_robot_pose)
8181
transform.header.frame_id = "map";
8282
transform.header.stamp = node->now();
8383
transform.child_frame_id = "base_link";
84-
broadcaster.sendTransform(transform);
84+
broadcaster->sendTransform(transform);
8585
EXPECT_NO_THROW(tracker.getRobotPose());
8686
}
8787

0 commit comments

Comments
 (0)