@@ -460,24 +460,26 @@ bool DockingServer::approachDock(Dock * dock, geometry_msgs::msg::PoseStamped &
460
460
geometry_msgs::msg::PoseStamped target_pose = dock_pose;
461
461
target_pose.header .stamp = rclcpp::Time (0 );
462
462
463
- // Make sure that the target pose is pointing at the robot when moving backwards
464
- // This is to ensure that the robot doesn't try to dock from the wrong side
465
- if (dock_backwards_) {
466
- target_pose.pose .orientation = nav2_util::geometry_utils::orientationAroundZAxis (
467
- tf2::getYaw (target_pose.pose .orientation ) + M_PI);
468
- }
463
+ const double backward_projection = 0.25 ;
464
+ const double yaw = tf2::getYaw (target_pose.pose .orientation );
469
465
470
466
// The control law can get jittery when close to the end when atan2's can explode.
471
467
// Thus, we backward project the controller's target pose a little bit after the
472
468
// dock so that the robot never gets to the end of the spiral before its in contact
473
469
// with the dock to stop the docking procedure.
474
- // (1 - 2 * dock_backwards_) converts `true` to -1 and `false` to 1
475
- const double backward_projection = 0.25 ;
476
- const double yaw = tf2::getYaw (target_pose.pose .orientation );
477
- target_pose.pose .position .x += (1 - 2 * dock_backwards_) * cos (yaw) * backward_projection;
478
- target_pose.pose .position .y += (1 - 2 * dock_backwards_) * sin (yaw) * backward_projection;
470
+ if (dock_backwards_) {
471
+ // Make sure that the target pose is pointing at the robot when moving backwards
472
+ // This is to ensure that the robot doesn't try to dock from the wrong side
473
+ target_pose.pose .orientation = nav2_util::geometry_utils::orientationAroundZAxis (
474
+ yaw + M_PI);
475
+ target_pose.pose .position .x -= cos (yaw) * backward_projection;
476
+ target_pose.pose .position .y -= sin (yaw) * backward_projection;
477
+ } else {
478
+ target_pose.pose .position .x += cos (yaw) * backward_projection;
479
+ target_pose.pose .position .y += sin (yaw) * backward_projection;
480
+ }
479
481
tf2_buffer_->transform (target_pose, target_pose, base_frame_);
480
-
482
+
481
483
// Compute and publish controls
482
484
auto command = std::make_unique<geometry_msgs::msg::TwistStamped>();
483
485
command->header .stamp = now ();
0 commit comments