Skip to content

Commit

Permalink
Fix transform time
Browse files Browse the repository at this point in the history
  • Loading branch information
redvinaa committed May 27, 2024
1 parent 7110324 commit 3e86e7b
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions nav2_controller/src/intermediate_planner_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -402,7 +402,7 @@ IntermediatePlannerServer::computePlan()
transformed_path.poses.reserve(global_path.poses.size());
for (auto & pose : global_path.poses) {
pose.header.frame_id = global_path.header.frame_id;
pose.header.stamp = get_clock()->now();
pose.header.stamp = rclcpp::Time(0);
geometry_msgs::msg::PoseStamped transformed_pose;
if (!costmap_ros_->transformPoseToGlobalFrame(pose, transformed_pose)) {
throw nav2_core::PlannerTFError("Failed to transform global path to costmap frame");
Expand Down Expand Up @@ -597,7 +597,7 @@ IntermediatePlannerServer::computePlan()
path_out_global.poses.reserve(path_out_local.poses.size());
for (auto & pose : path_out_local.poses) {
pose.header.frame_id = costmap_ros_->getGlobalFrameID();
pose.header.stamp = get_clock()->now();
pose.header.stamp = rclcpp::Time(0);
geometry_msgs::msg::PoseStamped transformed_pose;
try {
tf_->transform(pose, transformed_pose, global_path.header.frame_id);
Expand Down

0 comments on commit 3e86e7b

Please sign in to comment.