Skip to content

Commit

Permalink
Fix dock orientation while moving backwards
Browse files Browse the repository at this point in the history
Signed-off-by: Alberto Tudela <[email protected]>
  • Loading branch information
ajtudela committed Jul 9, 2024
1 parent 12a9c1d commit 940322a
Showing 1 changed file with 7 additions and 0 deletions.
7 changes: 7 additions & 0 deletions nav2_docking/opennav_docking/src/docking_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -414,6 +414,13 @@ bool DockingServer::approachDock(Dock * dock, geometry_msgs::msg::PoseStamped &
geometry_msgs::msg::PoseStamped target_pose = dock_pose;
target_pose.header.stamp = rclcpp::Time(0);

// Make sure that the target pose is pointing at the robot when moving backwards
// This is to ensure that the robot doesn't try to dock from the wrong side
if (dock_backwards_) {
target_pose.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(

Check warning on line 420 in nav2_docking/opennav_docking/src/docking_server.cpp

View check run for this annotation

Codecov / codecov/patch

nav2_docking/opennav_docking/src/docking_server.cpp#L420

Added line #L420 was not covered by tests
tf2::getYaw(target_pose.pose.orientation) + M_PI);
}

// The control law can get jittery when close to the end when atan2's can explode.
// Thus, we backward project the controller's target pose a little bit after the
// dock so that the robot never gets to the end of the spiral before its in contact
Expand Down

0 comments on commit 940322a

Please sign in to comment.