2323#include " nav2_core/controller_exceptions.hpp"
2424#include " nav2_ros_common/node_utils.hpp"
2525#include " nav2_util/geometry_utils.hpp"
26+ #include " nav2_util/path_utils.hpp"
2627#include " nav2_controller/controller_server.hpp"
2728
2829using namespace std ::chrono_literals;
@@ -43,6 +44,7 @@ ControllerServer::ControllerServer(const rclcpp::NodeOptions & options)
4344 lp_loader_ (" nav2_core" , " nav2_core::Controller" ),
4445 default_ids_{" FollowPath" },
4546 default_types_{" dwb_core::DWBLocalPlanner" },
47+ start_index_ (0 ),
4648 costmap_update_timeout_ (300ms)
4749{
4850 RCLCPP_INFO (get_logger (), " Creating controller server" );
@@ -65,6 +67,7 @@ ControllerServer::ControllerServer(const rclcpp::NodeOptions & options)
6567
6668 declare_parameter (" odom_topic" , rclcpp::ParameterValue (" odom" ));
6769 declare_parameter (" odom_duration" , rclcpp::ParameterValue (0.3 ));
70+ declare_parameter (" search_window" , rclcpp::ParameterValue (2.0 ));
6871
6972 // The costmap node is used in the implementation of the controller
7073 costmap_ros_ = std::make_shared<nav2_costmap_2d::Costmap2DROS>(
@@ -134,6 +137,7 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & state)
134137 get_parameter (" failure_tolerance" , failure_tolerance_);
135138 get_parameter (" use_realtime_priority" , use_realtime_priority_);
136139 get_parameter (" publish_zero_velocity" , publish_zero_velocity_);
140+ get_parameter (" search_window" , search_window_);
137141
138142 costmap_ros_->configure ();
139143 // Launch a thread to run the costmap node
@@ -225,6 +229,7 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & state)
225229
226230 odom_sub_ = std::make_unique<nav2_util::OdomSmoother>(node, odom_duration, odom_topic);
227231 vel_publisher_ = std::make_unique<nav2_util::TwistPublisher>(node, " cmd_vel" );
232+ tracking_feedback_pub_ = create_publisher<nav2_msgs::msg::TrackingFeedback>(" tracking_feedback" );
228233
229234 double costmap_update_timeout_dbl;
230235 get_parameter (" costmap_update_timeout" , costmap_update_timeout_dbl);
@@ -267,8 +272,8 @@ ControllerServer::on_activate(const rclcpp_lifecycle::State & /*state*/)
267272 it->second ->activate ();
268273 }
269274 vel_publisher_->on_activate ();
275+ tracking_feedback_pub_->on_activate ();
270276 action_server_->activate ();
271-
272277 auto node = shared_from_this ();
273278 // Add callback for dynamic parameters
274279 dyn_params_handler_ = node->add_on_set_parameters_callback (
@@ -302,6 +307,7 @@ ControllerServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
302307
303308 publishZeroVelocity ();
304309 vel_publisher_->on_deactivate ();
310+ tracking_feedback_pub_->on_deactivate ();
305311
306312 remove_on_set_parameters_callback (dyn_params_handler_.get ());
307313 dyn_params_handler_.reset ();
@@ -613,6 +619,7 @@ void ControllerServer::setPlannerPath(const nav_msgs::msg::Path & path)
613619 get_logger (), " Path end point is (%.2f, %.2f)" ,
614620 end_pose_.pose .position .x , end_pose_.pose .position .y );
615621
622+ start_index_ = 0 ;
616623 current_path_ = path;
617624}
618625
@@ -667,38 +674,56 @@ void ControllerServer::computeAndPublishVelocity()
667674 RCLCPP_DEBUG (get_logger (), " Publishing velocity at time %.2f" , now ().seconds ());
668675 publishVelocity (cmd_vel_2d);
669676
670- // Find the closest pose to current pose on global path
671- geometry_msgs::msg::PoseStamped robot_pose_in_path_frame;
677+ nav2_msgs::msg::TrackingFeedback current_tracking_feedback;
678+
679+ // Use the current robot pose's timestamp for the transformation
680+ end_pose_.header .stamp = pose.header .stamp ;
681+
672682 if (!nav2_util::transformPoseInTargetFrame (
673- pose, robot_pose_in_path_frame , *costmap_ros_->getTfBuffer (),
674- current_path_. header . frame_id , costmap_ros_->getTransformTolerance ()))
683+ end_pose_, transformed_end_pose_ , *costmap_ros_->getTfBuffer (),
684+ costmap_ros_-> getGlobalFrameID () , costmap_ros_->getTransformTolerance ()))
675685 {
676- throw nav2_core::ControllerTFError (" Failed to transform robot pose to path frame" );
686+ throw nav2_core::ControllerTFError (" Failed to transform end pose to global frame" );
677687 }
678688
679- std::shared_ptr<Action::Feedback> feedback = std::make_shared<Action::Feedback>();
680- feedback->speed = std::hypot (cmd_vel_2d.twist .linear .x , cmd_vel_2d.twist .linear .y );
689+ if (current_path_.poses .size () >= 2 ) {
690+ double current_distance_to_goal = nav2_util::geometry_utils::euclidean_distance (
691+ pose, transformed_end_pose_);
681692
682- nav_msgs::msg::Path & current_path = current_path_;
683- auto find_closest_pose_idx = [&robot_pose_in_path_frame, ¤t_path]()
693+ // Transform robot pose to path frame for path tracking calculations
694+ geometry_msgs::msg::PoseStamped robot_pose_in_path_frame;
695+ if (!nav2_util::transformPoseInTargetFrame (
696+ pose, robot_pose_in_path_frame, *costmap_ros_->getTfBuffer (),
697+ current_path_.header .frame_id , costmap_ros_->getTransformTolerance ()))
684698 {
685- size_t closest_pose_idx = 0 ;
686- double curr_min_dist = std::numeric_limits<double >::max ();
687- for (size_t curr_idx = 0 ; curr_idx < current_path.poses .size (); ++curr_idx) {
688- double curr_dist =
689- nav2_util::geometry_utils::euclidean_distance (robot_pose_in_path_frame,
690- current_path.poses [curr_idx]);
691- if (curr_dist < curr_min_dist) {
692- curr_min_dist = curr_dist;
693- closest_pose_idx = curr_idx;
694- }
695- }
696- return closest_pose_idx;
697- };
699+ throw nav2_core::ControllerTFError (" Failed to transform robot pose to path frame" );
700+ }
701+
702+ const auto path_search_result = nav2_util::distance_from_path (
703+ current_path_, robot_pose_in_path_frame.pose , start_index_, search_window_);
704+
705+ // Create tracking error message
706+ auto tracking_feedback_msg = std::make_unique<nav2_msgs::msg::TrackingFeedback>();
707+ tracking_feedback_msg->header = pose.header ;
708+ tracking_feedback_msg->tracking_error = path_search_result.distance ;
709+ tracking_feedback_msg->current_path_index = path_search_result.closest_segment_index ;
710+ tracking_feedback_msg->robot_pose = pose;
711+ tracking_feedback_msg->distance_to_goal = current_distance_to_goal;
712+ tracking_feedback_msg->speed = std::hypot (twist.linear .x , twist.linear .y );
713+ tracking_feedback_msg->remaining_path_length =
714+ nav2_util::geometry_utils::calculate_path_length (current_path_, start_index_);
715+ start_index_ = path_search_result.closest_segment_index ;
716+
717+ // Update current tracking error and publish
718+ current_tracking_feedback = *tracking_feedback_msg;
719+ if (tracking_feedback_pub_->get_subscription_count () > 0 ) {
720+ tracking_feedback_pub_->publish (std::move (tracking_feedback_msg));
721+ }
722+ }
698723
699- const std:: size_t closest_pose_idx = find_closest_pose_idx ();
700- feedback-> distance_to_goal = nav2_util::geometry_utils::calculate_path_length (current_path_,
701- closest_pose_idx) ;
724+ // Publish action feedback
725+ std::shared_ptr<Action::Feedback> feedback = std::make_shared<Action::Feedback>();
726+ feedback-> tracking_feedback = current_tracking_feedback ;
702727 action_server_->publish_feedback (feedback);
703728}
704729
@@ -798,14 +823,8 @@ bool ControllerServer::isGoalReached()
798823
799824 geometry_msgs::msg::Twist velocity = getThresholdedTwist (odom_sub_->getRawTwist ());
800825
801- geometry_msgs::msg::PoseStamped transformed_end_pose;
802- end_pose_.header .stamp = pose.header .stamp ;
803- nav2_util::transformPoseInTargetFrame (
804- end_pose_, transformed_end_pose, *costmap_ros_->getTfBuffer (),
805- costmap_ros_->getGlobalFrameID (), costmap_ros_->getTransformTolerance ());
806-
807826 return goal_checkers_[current_goal_checker_]->isGoalReached (
808- pose.pose , transformed_end_pose .pose ,
827+ pose.pose , transformed_end_pose_ .pose ,
809828 velocity);
810829}
811830
0 commit comments