Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Enable goals to be sent in other frames than the pre-configured global_frame #3917

Merged
merged 6 commits into from
Nov 15, 2023
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ class RemovePassedGoals : public BT::ActionNodeBase
double viapoint_achieved_radius_;
double transform_tolerance_;
std::shared_ptr<tf2_ros::Buffer> tf_;
std::string global_frame_, robot_base_frame_;
std::string robot_base_frame_;
};

} // namespace nav2_behavior_tree
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -92,7 +92,7 @@ class GoalReachedCondition : public BT::ConditionNode
bool initialized_;
double goal_reached_tol_;
double transform_tolerance_;
std::string global_frame_, robot_base_frame_;
std::string robot_base_frame_;
};

} // namespace nav2_behavior_tree
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,8 +37,6 @@ RemovePassedGoals::RemovePassedGoals(
auto node = config().blackboard->get<rclcpp::Node::SharedPtr>("node");
node->get_parameter("transform_tolerance", transform_tolerance_);

global_frame_ = BT::deconflictPortAndParamFrame<std::string, RemovePassedGoals>(
node, "global_frame", this);
robot_base_frame_ = BT::deconflictPortAndParamFrame<std::string, RemovePassedGoals>(
node, "robot_base_frame", this);
}
Expand All @@ -59,7 +57,7 @@ inline BT::NodeStatus RemovePassedGoals::tick()

geometry_msgs::msg::PoseStamped current_pose;
if (!nav2_util::getCurrentPose(
current_pose, *tf_, global_frame_, robot_base_frame_,
current_pose, *tf_, goal_poses[0].header.frame_id, robot_base_frame_,
transform_tolerance_))
{
return BT::NodeStatus::FAILURE;
Expand Down
10 changes: 4 additions & 6 deletions nav2_behavior_tree/plugins/condition/goal_reached_condition.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,8 +33,6 @@ GoalReachedCondition::GoalReachedCondition(
{
auto node = config().blackboard->get<rclcpp::Node::SharedPtr>("node");

global_frame_ = BT::deconflictPortAndParamFrame<std::string, GoalReachedCondition>(
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
node, "global_frame", this);
robot_base_frame_ = BT::deconflictPortAndParamFrame<std::string, GoalReachedCondition>(
node, "robot_base_frame", this);
}
Expand Down Expand Up @@ -73,17 +71,17 @@ void GoalReachedCondition::initialize()

bool GoalReachedCondition::isGoalReached()
{
geometry_msgs::msg::PoseStamped current_pose;
geometry_msgs::msg::PoseStamped goal;
getInput("goal", goal);

geometry_msgs::msg::PoseStamped current_pose;
if (!nav2_util::getCurrentPose(
current_pose, *tf_, global_frame_, robot_base_frame_, transform_tolerance_))
current_pose, *tf_, goal.header.frame_id, robot_base_frame_, transform_tolerance_))
{
RCLCPP_DEBUG(node_->get_logger(), "Current robot pose is not available.");
return false;
}

geometry_msgs::msg::PoseStamped goal;
getInput("goal", goal);
double dx = goal.pose.position.x - current_pose.pose.position.x;
double dy = goal.pose.position.y - current_pose.pose.position.y;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ class GoalReachedConditionTestFixture : public nav2_behavior_tree::BehaviorTreeT
R"(
<root main_tree_to_execute = "MainTree" >
<BehaviorTree ID="MainTree">
<GoalReached goal="{goal}" global_frame="map" robot_base_frame="base_link"/>
<GoalReached goal="{goal}" robot_base_frame="base_link"/>
</BehaviorTree>
</root>)";

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -104,8 +104,9 @@ class NavigateThroughPosesNavigator

/**
* @brief Goal pose initialization on the blackboard
* @return bool if goal was initialized successfully to be processed
*/
void initializeGoalPoses(ActionT::Goal::ConstSharedPtr goal);
bool initializeGoalPoses(ActionT::Goal::ConstSharedPtr goal);

rclcpp::Time start_time_;
std::string goals_blackboard_id_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -116,8 +116,9 @@ class NavigateToPoseNavigator
/**
* @brief Goal pose initialization on the blackboard
* @param goal Action template's goal message to process
* @return bool if goal was initialized successfully to be processed
*/
void initializeGoalPose(ActionT::Goal::ConstSharedPtr goal);
bool initializeGoalPose(ActionT::Goal::ConstSharedPtr goal);

rclcpp::Time start_time_;

Expand Down
48 changes: 36 additions & 12 deletions nav2_bt_navigator/src/navigators/navigate_through_poses.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -81,9 +81,7 @@ NavigateThroughPosesNavigator::goalReceived(ActionT::Goal::ConstSharedPtr goal)
return false;
}

initializeGoalPoses(goal);

return true;
return initializeGoalPoses(goal);
}

void
Expand Down Expand Up @@ -113,10 +111,14 @@ NavigateThroughPosesNavigator::onLoop()
}

geometry_msgs::msg::PoseStamped current_pose;
nav2_util::getCurrentPose(
current_pose, *feedback_utils_.tf,
feedback_utils_.global_frame, feedback_utils_.robot_frame,
feedback_utils_.transform_tolerance);
if (!nav2_util::getCurrentPose(
current_pose, *feedback_utils_.tf,
feedback_utils_.global_frame, feedback_utils_.robot_frame,
feedback_utils_.transform_tolerance))
{
RCLCPP_ERROR(logger_, "Robot pose is not available.");
return;
}

try {
// Get current path points
Expand Down Expand Up @@ -185,7 +187,13 @@ NavigateThroughPosesNavigator::onPreempt(ActionT::Goal::ConstSharedPtr goal)
// if pending goal requests the same BT as the current goal, accept the pending goal
// if pending goal has an empty behavior_tree field, it requests the default BT file
// accept the pending goal if the current goal is running the default BT file
initializeGoalPoses(bt_action_server_->acceptPendingGoal());
if (!initializeGoalPoses(bt_action_server_->acceptPendingGoal())) {
RCLCPP_WARN(
logger_,
"Preemption request was rejected since the goal poses could not be "
"transformed. For now, continuing to track the last goal until completion.");
bt_action_server_->terminatePendingGoal();
}
} else {
RCLCPP_WARN(
logger_,
Expand All @@ -198,13 +206,27 @@ NavigateThroughPosesNavigator::onPreempt(ActionT::Goal::ConstSharedPtr goal)
}
}

void
bool
NavigateThroughPosesNavigator::initializeGoalPoses(ActionT::Goal::ConstSharedPtr goal)
{
if (goal->poses.size() > 0) {
Goals goal_poses = goal->poses;
for (auto & goal_pose : goal_poses) {
if (!nav2_util::transformPoseInTargetFrame(
goal_pose, goal_pose, *feedback_utils_.tf, feedback_utils_.global_frame,
feedback_utils_.transform_tolerance))
{
RCLCPP_ERROR(
logger_,
"Failed to transform a goal pose provided with frame_id '%s' to the global frame '%s'.",
goal_pose.header.frame_id.c_str(), feedback_utils_.global_frame.c_str());
return false;
}
}

if (goal_poses.size() > 0) {
RCLCPP_INFO(
logger_, "Begin navigating from current location through %zu poses to (%.2f, %.2f)",
goal->poses.size(), goal->poses.back().pose.position.x, goal->poses.back().pose.position.y);
goal_poses.size(), goal_poses.back().pose.position.x, goal_poses.back().pose.position.y);
}

// Reset state for new action feedback
Expand All @@ -213,7 +235,9 @@ NavigateThroughPosesNavigator::initializeGoalPoses(ActionT::Goal::ConstSharedPtr
blackboard->set<int>("number_recoveries", 0); // NOLINT

// Update the goal pose on the blackboard
blackboard->set<Goals>(goals_blackboard_id_, goal->poses);
blackboard->set<Goals>(goals_blackboard_id_, std::move(goal_poses));

return true;
}

} // namespace nav2_bt_navigator
Expand Down
56 changes: 41 additions & 15 deletions nav2_bt_navigator/src/navigators/navigate_to_pose.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -94,9 +94,7 @@ NavigateToPoseNavigator::goalReceived(ActionT::Goal::ConstSharedPtr goal)
return false;
}

initializeGoalPose(goal);

return true;
return initializeGoalPose(goal);
}

void
Expand All @@ -114,10 +112,14 @@ NavigateToPoseNavigator::onLoop()
auto feedback_msg = std::make_shared<ActionT::Feedback>();

geometry_msgs::msg::PoseStamped current_pose;
nav2_util::getCurrentPose(
current_pose, *feedback_utils_.tf,
feedback_utils_.global_frame, feedback_utils_.robot_frame,
feedback_utils_.transform_tolerance);
if (!nav2_util::getCurrentPose(
current_pose, *feedback_utils_.tf,
feedback_utils_.global_frame, feedback_utils_.robot_frame,
feedback_utils_.transform_tolerance))
{
RCLCPP_ERROR(logger_, "Robot pose is not available.");
return;
}

auto blackboard = bt_action_server_->getBlackboard();

Expand Down Expand Up @@ -187,7 +189,13 @@ NavigateToPoseNavigator::onPreempt(ActionT::Goal::ConstSharedPtr goal)
// if pending goal requests the same BT as the current goal, accept the pending goal
// if pending goal has an empty behavior_tree field, it requests the default BT file
// accept the pending goal if the current goal is running the default BT file
initializeGoalPose(bt_action_server_->acceptPendingGoal());
if (!initializeGoalPose(bt_action_server_->acceptPendingGoal())) {
RCLCPP_WARN(
logger_,
"Preemption request was rejected since the goal pose could not be "
"transformed. For now, continuing to track the last goal until completion.");
bt_action_server_->terminatePendingGoal();
}
} else {
RCLCPP_WARN(
logger_,
Expand All @@ -200,27 +208,45 @@ NavigateToPoseNavigator::onPreempt(ActionT::Goal::ConstSharedPtr goal)
}
}

void
bool
NavigateToPoseNavigator::initializeGoalPose(ActionT::Goal::ConstSharedPtr goal)
{
geometry_msgs::msg::PoseStamped current_pose;
nav2_util::getCurrentPose(
current_pose, *feedback_utils_.tf,
feedback_utils_.global_frame, feedback_utils_.robot_frame,
feedback_utils_.transform_tolerance);
if (!nav2_util::getCurrentPose(
current_pose, *feedback_utils_.tf,
feedback_utils_.global_frame, feedback_utils_.robot_frame,
feedback_utils_.transform_tolerance))
{
RCLCPP_ERROR(logger_, "Initial robot pose is not available.");
return false;
}

geometry_msgs::msg::PoseStamped goal_pose;
if (!nav2_util::transformPoseInTargetFrame(
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
goal->pose, goal_pose, *feedback_utils_.tf, feedback_utils_.global_frame,
feedback_utils_.transform_tolerance))
{
RCLCPP_ERROR(
logger_,
"Failed to transform a goal pose provided with frame_id '%s' to the global frame '%s'.",
goal->pose.header.frame_id.c_str(), feedback_utils_.global_frame.c_str());
return false;
}

RCLCPP_INFO(
logger_, "Begin navigating from current location (%.2f, %.2f) to (%.2f, %.2f)",
current_pose.pose.position.x, current_pose.pose.position.y,
goal->pose.pose.position.x, goal->pose.pose.position.y);
goal_pose.pose.position.x, goal_pose.pose.position.y);

// Reset state for new action feedback
start_time_ = clock_->now();
auto blackboard = bt_action_server_->getBlackboard();
blackboard->set<int>("number_recoveries", 0); // NOLINT

// Update the goal pose on the blackboard
blackboard->set<geometry_msgs::msg::PoseStamped>(goal_blackboard_id_, goal->pose);
blackboard->set<geometry_msgs::msg::PoseStamped>(goal_blackboard_id_, goal_pose);

return true;
}

void
Expand Down