Skip to content
Snippets Groups Projects
Commit f00fa267 authored by Michael Jeronimo's avatar Michael Jeronimo Committed by Carl Delsey
Browse files

A couple missed changes to bt_navigator

parent 92b0ef2f
No related branches found
No related tags found
No related merge requests found
<!--
This Behavior Tree does the bare minimum - it invokes ComputePathToPose to
compute a path using the global planner. It then invokes the local planner
(FollowPath) with this path. The path endpoints (input to the global planner)
and the resulting path (output of the global planner and input to the local
planner) are passed on the blackboard.
This Behavior Tree does the minimum - it invokes ComputePathToPose once to compute a path
using the global planner. It then invokes the local planner (FollowPath) with this path.
-->
<root main_tree_to_execute="MainTree">
<BehaviorTree ID="MainTree">
<SequenceStar name="root">
<ComputePathToPose goal="${goal}" path="${path}"/>
<ComputePathToPose goal="${goal}"/>
<FollowPath path="${path}"/>
</SequenceStar>
</BehaviorTree>
......
......@@ -51,7 +51,7 @@ BtNavigator::on_configure(const rclcpp_lifecycle::State & /*state*/)
self_client_ = rclcpp_action::create_client<nav2_msgs::action::NavigateToPose>(
client_node_, "NavigateToPose");
goal_sub_ = rclcpp_node_->create_subscription<geometry_msgs::msg::PoseStamped>("goal",
goal_sub_ = rclcpp_node_->create_subscription<geometry_msgs::msg::PoseStamped>("/move_base_simple/goal",
rclcpp::SystemDefaultsQoS(),
std::bind(&BtNavigator::onGoalPoseReceived, this, std::placeholders::_1));
......
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment