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

Fix goal pose stamp (backport #4854) #4855

Merged
merged 1 commit into from
Jan 15, 2025
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 @@ -92,9 +92,10 @@ class PathHandler

/**
* @brief Get the global goal pose transformed to the local frame
* @param stamp Time to get the goal pose at
* @return Transformed goal pose
*/
geometry_msgs::msg::PoseStamped getTransformedGoal();
geometry_msgs::msg::PoseStamped getTransformedGoal(const builtin_interfaces::msg::Time & stamp);

protected:
/**
Expand Down
2 changes: 1 addition & 1 deletion nav2_mppi_controller/src/controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ geometry_msgs::msg::TwistStamped MPPIController::computeVelocityCommands(
#endif

std::lock_guard<std::mutex> param_lock(*parameters_handler_->getLock());
geometry_msgs::msg::Pose goal = path_handler_.getTransformedGoal().pose;
geometry_msgs::msg::Pose goal = path_handler_.getTransformedGoal(robot_pose.header.stamp).pose;

nav_msgs::msg::Path transformed_plan = path_handler_.transformPath(robot_pose);

Expand Down
6 changes: 4 additions & 2 deletions nav2_mppi_controller/src/path_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -186,10 +186,12 @@ void PathHandler::prunePlan(nav_msgs::msg::Path & plan, const PathIterator end)
plan.poses.erase(plan.poses.begin(), end);
}

geometry_msgs::msg::PoseStamped PathHandler::getTransformedGoal()
geometry_msgs::msg::PoseStamped PathHandler::getTransformedGoal(
const builtin_interfaces::msg::Time & stamp)
{
auto goal = global_plan_.poses.back();
goal.header = global_plan_.header;
goal.header.frame_id = global_plan_.header.frame_id;
goal.header.stamp = stamp;
if (goal.header.frame_id.empty()) {
throw nav2_core::ControllerTFError("Goal pose has an empty frame_id");
}
Expand Down
Loading