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
Original file line number Diff line number Diff line change
Expand Up @@ -256,7 +256,7 @@ class ControllerServer : public nav2_util::LifecycleNode
double failure_tolerance_;

// Whether we've published the single controller warning yet
geometry_msgs::msg::Pose end_pose_;
geometry_msgs::msg::PoseStamped end_pose_;

// Last time the controller generated a valid command
rclcpp::Time last_valid_cmd_time_;
Expand Down
23 changes: 14 additions & 9 deletions nav2_controller/src/controller_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -429,18 +429,14 @@ void ControllerServer::setPlannerPath(const nav_msgs::msg::Path & path)
}
controllers_[current_controller_]->setPlan(path);

auto end_pose = path.poses.back();
end_pose.header.frame_id = path.header.frame_id;
rclcpp::Duration tolerance(rclcpp::Duration::from_seconds(costmap_ros_->getTransformTolerance()));
nav_2d_utils::transformPose(
costmap_ros_->getTfBuffer(), costmap_ros_->getGlobalFrameID(),
end_pose, end_pose, tolerance);
end_pose_ = path.poses.back();
end_pose_.header.frame_id = path.header.frame_id;
goal_checkers_[current_goal_checker_]->reset();

RCLCPP_DEBUG(
get_logger(), "Path end point is (%.2f, %.2f)",
end_pose.pose.position.x, end_pose.pose.position.y);
end_pose_ = end_pose.pose;
end_pose_.pose.position.x, end_pose_.pose.position.y);

current_path_ = path;
}

Expand Down Expand Up @@ -567,7 +563,16 @@ bool ControllerServer::isGoalReached()

nav_2d_msgs::msg::Twist2D twist = getThresholdedTwist(odom_sub_->getTwist());
geometry_msgs::msg::Twist velocity = nav_2d_utils::twist2Dto3D(twist);
return goal_checkers_[current_goal_checker_]->isGoalReached(pose.pose, end_pose_, velocity);

geometry_msgs::msg::PoseStamped transformed_end_pose;
rclcpp::Duration tolerance(rclcpp::Duration::from_seconds(costmap_ros_->getTransformTolerance()));
nav_2d_utils::transformPose(
costmap_ros_->getTfBuffer(), costmap_ros_->getGlobalFrameID(),
end_pose_, transformed_end_pose, tolerance);

return goal_checkers_[current_goal_checker_]->isGoalReached(
pose.pose, transformed_end_pose.pose,
velocity);
}

bool ControllerServer::getRobotPose(geometry_msgs::msg::PoseStamped & pose)
Expand Down