@@ -60,6 +60,8 @@ void RotationShimController::configure(
6060 node, plugin_name_ + " .simulate_ahead_time" , rclcpp::ParameterValue (1.0 ));
6161 nav2_util::declare_parameter_if_not_declared (
6262 node, plugin_name_ + " .primary_controller" , rclcpp::PARAMETER_STRING);
63+ nav2_util::declare_parameter_if_not_declared (
64+ node, plugin_name_ + " .rotate_to_goal_heading" , rclcpp::ParameterValue (false ));
6365
6466 node->get_parameter (plugin_name_ + " .angular_dist_threshold" , angular_dist_threshold_);
6567 node->get_parameter (plugin_name_ + " .forward_sampling_distance" , forward_sampling_distance_);
@@ -73,6 +75,8 @@ void RotationShimController::configure(
7375 node->get_parameter (" controller_frequency" , control_frequency);
7476 control_duration_ = 1.0 / control_frequency;
7577
78+ node->get_parameter (" rotate_to_goal_heading" , rotate_to_goal_heading_);
79+
7680 try {
7781 primary_controller_ = lp_loader_.createUniqueInstance (primary_controller);
7882 RCLCPP_INFO (
@@ -134,11 +138,71 @@ void RotationShimController::cleanup()
134138 primary_controller_.reset ();
135139}
136140
141+ /* *
142+ * @brief Check if the robot pose is within the Goal Checker's tolerances to goal
143+ * @param global_checker Pointer to the goal checker
144+ * @param robot Pose of robot
145+ * @param path Path to retreive goal pose from
146+ * @return bool If robot is within goal checker tolerances to the goal
147+ */
148+ static bool withinPositionGoalTolerance (
149+ nav2_core::GoalChecker * goal_checker,
150+ const geometry_msgs::msg::Pose & robot,
151+ const geometry_msgs::msg::Pose & goal)
152+ {
153+ if (goal_checker) {
154+ geometry_msgs::msg::Pose pose_tolerance;
155+ geometry_msgs::msg::Twist velocity_tolerance;
156+ goal_checker->getTolerances (pose_tolerance, velocity_tolerance);
157+
158+ const auto pose_tolerance_sq = pose_tolerance.position .x * pose_tolerance.position .x ;
159+
160+ auto dx = robot.position .x - goal.position .x ;
161+ auto dy = robot.position .y - goal.position .y ;
162+
163+ auto dist_sq = dx * dx + dy * dy;
164+
165+ if (dist_sq < pose_tolerance_sq) {
166+ return true ;
167+ }
168+ }
169+
170+ return false ;
171+ }
172+
137173geometry_msgs::msg::TwistStamped RotationShimController::computeVelocityCommands (
138174 const geometry_msgs::msg::PoseStamped & pose,
139175 const geometry_msgs::msg::Twist & velocity,
140176 nav2_core::GoalChecker * goal_checker)
141177{
178+ // Rotate to goal heading when in goal xy tolerance
179+ if (rotate_to_goal_heading_) {
180+ std::lock_guard<std::mutex> lock_reinit (mutex_);
181+
182+ try {
183+ geometry_msgs::msg::Pose sampled_pt_goal = transformPoseToBaseFrame (getSampledPathGoal ());
184+ if (withinPositionGoalTolerance (goal_checker, pose.pose , sampled_pt_goal)) {
185+ double pose_yaw, pose_pitch, pose_roll;
186+ double goal_yaw, goal_pitch, goal_roll;
187+ tf2::getEulerYPR (pose.pose .orientation , pose_yaw, pose_pitch, pose_roll);
188+ tf2::getEulerYPR (sampled_pt_goal.orientation , goal_yaw, goal_pitch, goal_roll);
189+
190+ double angular_distance_to_heading = std::abs (goal_yaw - pose_yaw);
191+ if (angular_distance_to_heading > M_PI) {
192+ angular_distance_to_heading -= M_PI;
193+ }
194+
195+ return computeRotateToHeadingCommand (angular_distance_to_heading, pose, velocity);
196+ }
197+ } catch (const std::runtime_error & e) {
198+ RCLCPP_INFO (
199+ logger_,
200+ " Rotation Shim Controller was unable to find a goal point,"
201+ " a rotational collision was detected, or TF failed to transform"
202+ " into base frame! what(): %s" , e.what ());
203+ }
204+ }
205+
142206 if (path_updated_) {
143207 nav2_costmap_2d::Costmap2D * costmap = costmap_ros_->getCostmap ();
144208 std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t > lock (*(costmap->getMutex ()));
@@ -201,6 +265,16 @@ geometry_msgs::msg::PoseStamped RotationShimController::getSampledPathPt()
201265 " passing off to primary controller plugin." , forward_sampling_distance_));
202266}
203267
268+ geometry_msgs::msg::PoseStamped RotationShimController::getSampledPathGoal ()
269+ {
270+ if (current_path_.poses .size () == 0 ) {
271+ throw nav2_core::ControllerException (
272+ " Path is empty - cannot find a goal point" );
273+ }
274+
275+ return current_path_.poses [current_path_.poses .size () - 1 ];
276+ }
277+
204278geometry_msgs::msg::Pose
205279RotationShimController::transformPoseToBaseFrame (const geometry_msgs::msg::PoseStamped & pt)
206280{
@@ -306,6 +380,9 @@ RotationShimController::dynamicParametersCallback(std::vector<rclcpp::Parameter>
306380 simulate_ahead_time_ = parameter.as_double ();
307381 }
308382 }
383+ if (name == plugin_name_ + " .rotate_to_goal_heading" ) {
384+ rotate_to_goal_heading_ = parameter.as_bool ();
385+ }
309386 }
310387
311388 result.successful = true ;
0 commit comments