diff --git a/nav2_mppi_controller/CMakeLists.txt b/nav2_mppi_controller/CMakeLists.txt index 1ce40c2cfa..a315850fdb 100644 --- a/nav2_mppi_controller/CMakeLists.txt +++ b/nav2_mppi_controller/CMakeLists.txt @@ -28,7 +28,6 @@ set(dependencies_pkgs geometry_msgs visualization_msgs nav_msgs - nav2_msgs nav2_core nav2_costmap_2d nav2_util diff --git a/nav2_mppi_controller/src/controller.cpp b/nav2_mppi_controller/src/controller.cpp index 104800c0fd..859301792c 100644 --- a/nav2_mppi_controller/src/controller.cpp +++ b/nav2_mppi_controller/src/controller.cpp @@ -124,7 +124,7 @@ geometry_msgs::msg::TwistStamped MPPIController::computeVelocityCommands( // log critic names and costs for (size_t i = 0; i < critic_names.size(); i++) { - RCLCPP_INFO(logger_, "Critic: %s, Cost: %f", critic_names[i].c_str(), critic_costs[i]); + RCLCPP_DEBUG(logger_, "Critic: %s, Cost: %f", critic_names[i].c_str(), critic_costs[i]); } // make msg diff --git a/nav2_mppi_controller/src/critic_manager.cpp b/nav2_mppi_controller/src/critic_manager.cpp index 3952a97b08..85f521f38a 100644 --- a/nav2_mppi_controller/src/critic_manager.cpp +++ b/nav2_mppi_controller/src/critic_manager.cpp @@ -85,9 +85,6 @@ void CriticManager::evalTrajectoriesScores( xt::xtensor CriticManager::evalTrajectory( CriticData & data) const { - // log the critic_scores shape - RCLCPP_INFO(logger_, "(BEFORE FOR)"); - xt::xtensor critic_scores = xt::zeros({critics_.size()}); for (size_t q = 0; q < critics_.size(); q++) { @@ -99,8 +96,6 @@ xt::xtensor CriticManager::evalTrajectory( critics_[q]->score(data); critic_scores(q) = data.costs[0]; } - // log the for cycle finished in criticmanager - RCLCPP_INFO(logger_, "CriticManager: Critic evaluation (FOR) finished"); return critic_scores; }