diff --git a/nav2_route/test/test_goal_intent_extractor.cpp b/nav2_route/test/test_goal_intent_extractor.cpp index 21c49708193..26077eb25cc 100644 --- a/nav2_route/test/test_goal_intent_extractor.cpp +++ b/nav2_route/test/test_goal_intent_extractor.cpp @@ -83,7 +83,7 @@ TEST(GoalIntentExtractorTest, test_transform_pose) node->get_node_timers_interface()); tf->setCreateTimerInterface(timer_interface); auto transform_listener = std::make_shared(*tf); - tf2_ros::TransformBroadcaster broadcaster(node); + auto broadcaster = std::make_shared(node); std::shared_ptr costmap_subscriber = nullptr; extractor.configure(node, graph, &id_map, tf, costmap_subscriber, "map", "base_link"); @@ -101,7 +101,7 @@ TEST(GoalIntentExtractorTest, test_transform_pose) transform.header.frame_id = "map"; transform.header.stamp = node->now(); transform.child_frame_id = "gps"; - broadcaster.sendTransform(transform); + broadcaster->sendTransform(transform); EXPECT_NO_THROW(extractor.transformPose(pose, "map")); } diff --git a/nav2_route/test/test_route_tracker.cpp b/nav2_route/test/test_route_tracker.cpp index 07ca24a4e91..cfe808b8ac2 100644 --- a/nav2_route/test/test_route_tracker.cpp +++ b/nav2_route/test/test_route_tracker.cpp @@ -69,7 +69,7 @@ TEST(RouteTrackerTest, test_get_robot_pose) node->get_node_timers_interface()); tf->setCreateTimerInterface(timer_interface); auto transform_listener = std::make_shared(*tf); - tf2_ros::TransformBroadcaster broadcaster(node); + auto broadcaster = std::make_shared(node); std::shared_ptr costmap_subscriber; RouteTracker tracker; @@ -81,7 +81,7 @@ TEST(RouteTrackerTest, test_get_robot_pose) transform.header.frame_id = "map"; transform.header.stamp = node->now(); transform.child_frame_id = "base_link"; - broadcaster.sendTransform(transform); + broadcaster->sendTransform(transform); EXPECT_NO_THROW(tracker.getRobotPose()); }