Skip to content

Commit

Permalink
[RotationShimController] fix: rotate on short paths (#4716)
Browse files Browse the repository at this point in the history
Add header data to goal for short paths.

Commit d8ae3c1 added the possibility to
the rotation shim controller to rotate towards the goal when the goal
was closer that the `forward_sampling_distance`. This feature was not
fully working as the goal was missing proper header data, causing the
rotation shim to give back control to the main controller.

Co-authored-by: agennart <[email protected]>
  • Loading branch information
2 people authored and SteveMacenski committed Nov 8, 2024
1 parent bc94198 commit 6bff7de
Showing 1 changed file with 4 additions and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -248,7 +248,10 @@ geometry_msgs::msg::PoseStamped RotationShimController::getSampledPathPt()
}
}

return current_path_.poses.back();
auto goal = current_path_.poses.back();
goal.header.frame_id = current_path_.header.frame_id;
goal.header.stamp = clock_->now();
return goal;
}

geometry_msgs::msg::PoseStamped RotationShimController::getSampledPathGoal()
Expand Down

0 comments on commit 6bff7de

Please sign in to comment.