Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
12 changes: 12 additions & 0 deletions nav2_util/include/nav2_util/simple_action_server.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -390,6 +390,18 @@ class SimpleActionServer
return current_handle_->get_goal();
}

const rclcpp_action::GoalUUID get_current_goal_id() const
{
std::lock_guard<std::recursive_mutex> lock(update_mutex_);

if (!is_active(current_handle_)) {
error_msg("A goal is not available or has reached a final state");
return rclcpp_action::GoalUUID();
}

return current_handle_->get_goal_id();
}

/**
* @brief Get the pending goal object
* @return Goal Ptr to the goal that's pending
Expand Down
7 changes: 7 additions & 0 deletions nav2_waypoint_follower/src/waypoint_follower.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -286,6 +286,13 @@ void
WaypointFollower::resultCallback(
const rclcpp_action::ClientGoalHandle<ClientT>::WrappedResult & result)
{
if (result.goal_id != future_goal_handle_.get()->get_goal_id()) {
RCLCPP_DEBUG(
get_logger(),
"Goal IDs do not match for the current goal handle and received result."
"Ignoring likely due to receiving result for an old goal.");
}

switch (result.code) {
case rclcpp_action::ResultCode::SUCCEEDED:
current_goal_status_ = ActionStatus::SUCCEEDED;
Expand Down