Skip to content

Commit dacfc42

Browse files
sandeepduttamasf7g
authored andcommitted
Merged Fix navfn_planner from humble PR ros-navigation#5087 (ros-navigation#5092)
* merged changes from humble for goal.header fix * reverted back, error in merge * ported goal.header fix in navfn_planner.cpp from humble * reverted to navfn_planner.cpp to origin/main * merged navfn_planner.cpp from humble * fixed the merge
1 parent 354a0d0 commit dacfc42

File tree

1 file changed

+2
-0
lines changed

1 file changed

+2
-0
lines changed

nav2_navfn_planner/src/navfn_planner.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -368,6 +368,7 @@ NavfnPlanner::smoothApproachToGoal(
368368
}
369369
geometry_msgs::msg::PoseStamped goal_copy;
370370
goal_copy.pose = goal;
371+
goal_copy.header = plan.header;
371372
plan.poses.push_back(goal_copy);
372373
}
373374

@@ -417,6 +418,7 @@ NavfnPlanner::getPlanFromPotential(
417418
mapToWorld(x[i], y[i], world_x, world_y);
418419

419420
geometry_msgs::msg::PoseStamped pose;
421+
pose.header = plan.header;
420422
pose.pose.position.x = world_x;
421423
pose.pose.position.y = world_y;
422424
pose.pose.position.z = 0.0;

0 commit comments

Comments
 (0)