@@ -618,6 +618,7 @@ void ControllerServer::setPlannerPath(const nav_msgs::msg::Path & path)
618
618
get_logger (), " Path end point is (%.2f, %.2f)" ,
619
619
end_pose_.pose .position .x , end_pose_.pose .position .y );
620
620
621
+ // start from zero with every new path
621
622
start_index_ = 0 ;
622
623
current_path_ = path;
623
624
}
@@ -769,18 +770,40 @@ void ControllerServer::publishTrackingState()
769
770
return ;
770
771
}
771
772
772
- const double distance_to_goal = nav2_util::geometry_utils::euclidean_distance (robot_pose,
773
- end_pose_);
774
- const auto path_search_result = nav2_util::distance_from_path (current_path_, robot_pose.pose ,
775
- start_index_, search_window_);
773
+ // Frame checks
774
+ geometry_msgs::msg::PoseStamped robot_pose_in_path_frame;
775
+ if (!nav2_util::transformPoseInTargetFrame (
776
+ robot_pose, robot_pose_in_path_frame, *costmap_ros_->getTfBuffer (),
777
+ current_path_.header .frame_id , costmap_ros_->getTransformTolerance ()))
778
+ {
779
+ RCLCPP_WARN (get_logger (), " Failed to transform robot pose to path frame." );
780
+ return ;
781
+ }
782
+
783
+ geometry_msgs::msg::PoseStamped end_pose_in_robot_frame;
784
+ if (!nav2_util::transformPoseInTargetFrame (
785
+ end_pose_, end_pose_in_robot_frame, *costmap_ros_->getTfBuffer (),
786
+ robot_pose.header .frame_id , costmap_ros_->getTransformTolerance ()))
787
+ {
788
+ RCLCPP_WARN (get_logger (), " Failed to transform end pose to robot frame." );
789
+ return ;
790
+ }
791
+
792
+ const double distance_to_goal = nav2_util::geometry_utils::euclidean_distance (
793
+ robot_pose, end_pose_in_robot_frame);
794
+
795
+ const auto path_search_result = nav2_util::distance_from_path (
796
+ current_path_, robot_pose_in_path_frame.pose , start_index_, search_window_);
797
+
776
798
const size_t closest_idx = path_search_result.closest_segment_index ;
777
799
start_index_ = closest_idx;
778
800
779
801
const auto & segment_start = current_path_.poses [closest_idx];
780
802
const auto & segment_end = current_path_.poses [closest_idx + 1 ];
781
803
804
+ // Cross product is for getting which side of the track
782
805
double cross_product = nav2_util::geometry_utils::cross_product_2d (
783
- robot_pose .pose .position , segment_start.pose , segment_end.pose );
806
+ robot_pose_in_path_frame .pose .position , segment_start.pose , segment_end.pose );
784
807
785
808
nav2_msgs::msg::TrackingError tracking_error_msg;
786
809
tracking_error_msg.header .stamp = now ();
0 commit comments