Skip to content

Commit

Permalink
Fix goal pose stamp
Browse files Browse the repository at this point in the history
Signed-off-by: redvinaa <redvinaa@gmail.com>
  • Loading branch information
redvinaa committed Jan 15, 2025
1 parent d11de56 commit e6b478b
Show file tree
Hide file tree
Showing 3 changed files with 7 additions and 4 deletions.
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

0 comments on commit e6b478b

Please sign in to comment.