Skip to content

Commit

Permalink
[RotationShimController] fix: rotate to goal heading (#4724)
Browse files Browse the repository at this point in the history
Add frame_id to goal when rotating towards goal heading, otherwise the
transform would fail. This bug was introduced in 30e2cde by not setting
the frame_id.

Signed-off-by: agennart <[email protected]>
Co-authored-by: agennart <[email protected]>
  • Loading branch information
2 people authored and SteveMacenski committed Nov 8, 2024
1 parent 3b8846b commit eedcae7
Showing 1 changed file with 1 addition and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -259,6 +259,7 @@ geometry_msgs::msg::PoseStamped RotationShimController::getSampledPathGoal()
}

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

0 comments on commit eedcae7

Please sign in to comment.