Skip to content

Commit 30f2163

Browse files
authored
Fix goal pose stamp (#4856)
Signed-off-by: redvinaa <redvinaa@gmail.com>
1 parent ad2f960 commit 30f2163

File tree

3 files changed

+7
-4
lines changed

3 files changed

+7
-4
lines changed

nav2_mppi_controller/include/nav2_mppi_controller/tools/path_handler.hpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -91,9 +91,10 @@ class PathHandler
9191

9292
/**
9393
* @brief Get the global goal pose transformed to the local frame
94+
* @param stamp Time to get the goal pose at
9495
* @return Transformed goal pose
9596
*/
96-
geometry_msgs::msg::PoseStamped getTransformedGoal();
97+
geometry_msgs::msg::PoseStamped getTransformedGoal(const builtin_interfaces::msg::Time & stamp);
9798

9899
protected:
99100
/**

nav2_mppi_controller/src/controller.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -92,7 +92,7 @@ geometry_msgs::msg::TwistStamped MPPIController::computeVelocityCommands(
9292
last_time_called_ = clock_->now();
9393

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

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

nav2_mppi_controller/src/path_handler.cpp

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -186,10 +186,12 @@ void PathHandler::prunePlan(nav_msgs::msg::Path & plan, const PathIterator end)
186186
plan.poses.erase(plan.poses.begin(), end);
187187
}
188188

189-
geometry_msgs::msg::PoseStamped PathHandler::getTransformedGoal()
189+
geometry_msgs::msg::PoseStamped PathHandler::getTransformedGoal(
190+
const builtin_interfaces::msg::Time & stamp)
190191
{
191192
auto goal = global_plan_.poses.back();
192-
goal.header = global_plan_.header;
193+
goal.header.frame_id = global_plan_.header.frame_id;
194+
goal.header.stamp = stamp;
193195
if (goal.header.frame_id.empty()) {
194196
throw std::runtime_error("Goal pose has an empty frame_id");
195197
}

0 commit comments

Comments
 (0)