Skip to content

Commit fa9aaa9

Browse files
gennartanagennart
andauthored
[RotationShimController] fix: rotate on short paths (#4716)
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 <antoine.gennart@quimesis.be>
1 parent 6311978 commit fa9aaa9

File tree

1 file changed

+4
-1
lines changed

1 file changed

+4
-1
lines changed

‎nav2_rotation_shim_controller/src/nav2_rotation_shim_controller.cpp‎

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -253,7 +253,10 @@ geometry_msgs::msg::PoseStamped RotationShimController::getSampledPathPt()
253253
}
254254
}
255255

256-
return current_path_.poses.back();
256+
auto goal = current_path_.poses.back();
257+
goal.header.frame_id = current_path_.header.frame_id;
258+
goal.header.stamp = clock_->now();
259+
return goal;
257260
}
258261

259262
geometry_msgs::msg::PoseStamped RotationShimController::getSampledPathGoal()

0 commit comments

Comments
 (0)