Skip to content
Snippets Groups Projects
Unverified Commit ed8ddafb authored by Michael Ferguson's avatar Michael Ferguson Committed by GitHub
Browse files

transform goal to costmap frame (#1949)

The plan recieved is usually in global frame, but
our local costmap is often in odom frame. This
fixes a regression from #1857
parent d616e496
No related branches found
No related tags found
No related merge requests found
......@@ -20,6 +20,7 @@
#include "nav2_core/exceptions.hpp"
#include "nav_2d_utils/conversions.hpp"
#include "nav_2d_utils/tf_help.hpp"
#include "nav2_util/node_utils.hpp"
#include "nav2_util/geometry_utils.hpp"
#include "nav2_controller/nav2_controller.hpp"
......@@ -336,6 +337,11 @@ 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(costmap_ros_->getTransformTolerance() * 1e9);
nav_2d_utils::transformPose(
costmap_ros_->getTfBuffer(), costmap_ros_->getGlobalFrameID(),
end_pose, end_pose, tolerance);
goal_checker_->reset();
RCLCPP_DEBUG(
......
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