Skip to content

Commit 13d6629

Browse files
authored
Fix some parameters not being passed to getCurrentPose (#1790)
Signed-off-by: ymd-stella <world.applepie@gmail.com>
1 parent 4708b59 commit 13d6629

File tree

3 files changed

+7
-2
lines changed

3 files changed

+7
-2
lines changed

‎nav2_behavior_tree/plugins/condition/goal_reached_condition.cpp‎

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -82,7 +82,9 @@ class GoalReachedCondition : public BT::ConditionNode
8282
{
8383
geometry_msgs::msg::PoseStamped current_pose;
8484

85-
if (!nav2_util::getCurrentPose(current_pose, *tf_, "map", "base_link", transform_tolerance_)) {
85+
if (!nav2_util::getCurrentPose(
86+
current_pose, *tf_, global_frame_, robot_base_frame_, transform_tolerance_))
87+
{
8688
RCLCPP_DEBUG(node_->get_logger(), "Current robot pose is not available.");
8789
return false;
8890
}

‎nav2_bt_navigator/include/nav2_bt_navigator/bt_navigator.hpp‎

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -140,6 +140,7 @@ class BtNavigator : public nav2_util::LifecycleNode
140140
rclcpp::Time start_time_;
141141
std::string robot_frame_;
142142
std::string global_frame_;
143+
double transform_tolerance_;
143144
};
144145

145146
} // namespace nav2_bt_navigator

‎nav2_bt_navigator/src/bt_navigator.cpp‎

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -110,6 +110,7 @@ BtNavigator::on_configure(const rclcpp_lifecycle::State & /*state*/)
110110
plugin_lib_names_ = get_parameter("plugin_lib_names").as_string_array();
111111
global_frame_ = get_parameter("global_frame").as_string();
112112
robot_frame_ = get_parameter("robot_base_frame").as_string();
113+
transform_tolerance_ = get_parameter("transform_tolerance").as_double();
113114

114115
// Create the class that registers our custom nodes and executes the BT
115116
bt_ = std::make_unique<nav2_behavior_tree::BehaviorTreeEngine>(plugin_lib_names_);
@@ -242,7 +243,8 @@ BtNavigator::navigateToPose()
242243

243244
// action server feedback (pose, duration of task,
244245
// number of recoveries, and distance remaining to goal)
245-
nav2_util::getCurrentPose(feedback_msg->current_pose, *tf_);
246+
nav2_util::getCurrentPose(
247+
feedback_msg->current_pose, *tf_, global_frame_, robot_frame_, transform_tolerance_);
246248

247249
geometry_msgs::msg::PoseStamped goal_pose;
248250
blackboard_->get("goal", goal_pose);

0 commit comments

Comments
 (0)