Skip to content

Commit 44a69cc

Browse files
gennartanagennart
andauthored
[RotationShimController] fix: rotate to goal heading (#4724)
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 <antoine.gennart@quimesis.be> Co-authored-by: agennart <antoine.gennart@quimesis.be>
1 parent c7ef3be commit 44a69cc

File tree

1 file changed

+1
-0
lines changed

1 file changed

+1
-0
lines changed

‎nav2_rotation_shim_controller/src/nav2_rotation_shim_controller.cpp‎

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -269,6 +269,7 @@ geometry_msgs::msg::PoseStamped RotationShimController::getSampledPathGoal()
269269
}
270270

271271
auto goal = current_path_.poses.back();
272+
goal.header.frame_id = current_path_.header.frame_id;
272273
goal.header.stamp = clock_->now();
273274
return goal;
274275
}

0 commit comments

Comments
��(0)