diff --git a/nav2_bt_navigator/src/bt_navigator.cpp b/nav2_bt_navigator/src/bt_navigator.cpp index 6740dc80d44606a7daa69de62c9f6cbec5d9efc4..dfd3780e2a8c0657b12fa3512e7d1b31b29e32f5 100644 --- a/nav2_bt_navigator/src/bt_navigator.cpp +++ b/nav2_bt_navigator/src/bt_navigator.cpp @@ -56,7 +56,7 @@ BtNavigator::on_configure(const rclcpp_lifecycle::State & /*state*/) client_node_, "NavigateToPose"); goal_sub_ = rclcpp_node_->create_subscription<geometry_msgs::msg::PoseStamped>( - "/move_base_simple/goal", + "/goal_pose", rclcpp::SystemDefaultsQoS(), std::bind(&BtNavigator::onGoalPoseReceived, this, std::placeholders::_1)); diff --git a/nav2_system_tests/src/system/test_system_node.py b/nav2_system_tests/src/system/test_system_node.py index a73285e73bda55fec435cc64947b7ca9636d38f5..35ecc24c206279939d34b1cc1e5cc1574a488cc4 100755 --- a/nav2_system_tests/src/system/test_system_node.py +++ b/nav2_system_tests/src/system/test_system_node.py @@ -31,7 +31,7 @@ class NavTester(Node): super().__init__('nav2_tester') self.initial_pose_pub = self.create_publisher(PoseWithCovarianceStamped, '/initialpose') - self.goal_pub = self.create_publisher(PoseStamped, '/move_base_simple/goal') + self.goal_pub = self.create_publisher(PoseStamped, '/goal_pose') self.model_pose_sub = self.create_subscription(PoseWithCovarianceStamped, '/amcl_pose', self.poseCallback)