diff --git a/nav2_controller/src/controller_server.cpp b/nav2_controller/src/controller_server.cpp index 98a6eda8629..e3c32530f4c 100644 --- a/nav2_controller/src/controller_server.cpp +++ b/nav2_controller/src/controller_server.cpp @@ -511,6 +511,7 @@ void ControllerServer::computeControl() get_logger(), "Control loop missed its desired rate of %.4f Hz. Current loop rate is %.4f Hz.", controller_frequency_, 1 / cycle_duration.seconds()); + loop_rate.reset(); } } } catch (nav2_core::InvalidController & e) { @@ -645,7 +646,7 @@ void ControllerServer::computeAndPublishVelocity() // other types will not be resolved with more attempts } catch (nav2_core::NoValidControl & e) { if (failure_tolerance_ > 0 || failure_tolerance_ == -1.0) { - RCLCPP_WARN(this->get_logger(), "%s", e.what()); + RCLCPP_WARN(this->get_logger(), "Controller error, but still below failure tolerance. Error: %s", e.what()); cmd_vel_2d.twist.angular.x = 0; cmd_vel_2d.twist.angular.y = 0; cmd_vel_2d.twist.angular.z = 0; @@ -657,6 +658,7 @@ void ControllerServer::computeAndPublishVelocity() if ((now() - last_valid_cmd_time_).seconds() > failure_tolerance_ && failure_tolerance_ != -1.0) { + RCLCPP_ERROR(this->get_logger(), "Controller error and failure tolerance exceeded. Error: %s", e.what()); throw nav2_core::PatienceExceeded("Controller patience exceeded"); } } else { diff --git a/nav2_mppi_controller/src/path_handler.cpp b/nav2_mppi_controller/src/path_handler.cpp index 55931f6bc62..966b2e7ff3e 100644 --- a/nav2_mppi_controller/src/path_handler.cpp +++ b/nav2_mppi_controller/src/path_handler.cpp @@ -128,7 +128,7 @@ nav_msgs::msg::Path PathHandler::transformPath( geometry_msgs::msg::PoseStamped global_pose = transformToGlobalPlanFrame(robot_pose); auto [transformed_plan, lower_bound] = getGlobalPlanConsideringBoundsInCostmapFrame(global_pose); - + const auto prev_size = global_plan_up_to_inversion_.poses.size(); prunePlan(global_plan_up_to_inversion_, lower_bound); if (enforce_path_inversion_ && inversion_locale_ != 0u) { @@ -140,7 +140,10 @@ nav_msgs::msg::Path PathHandler::transformPath( } if (transformed_plan.poses.empty()) { - throw nav2_core::InvalidPath("Resulting plan has 0 poses in it."); + throw nav2_core::InvalidPath("Resulting plan has 0 poses in it, while global plan has " + + std::to_string(global_plan_.poses.size()) + " poses. lower_bound index: " + + std::to_string(lower_bound - global_plan_.poses.begin()) + + ". prev_size: " + std::to_string(prev_size) + "."); } return transformed_plan;