Skip to content

Commit

Permalink
remove unnecessary logging
Browse files Browse the repository at this point in the history
  • Loading branch information
turtlewizard73 committed Dec 14, 2024
1 parent 0a81beb commit 1f8c9b0
Show file tree
Hide file tree
Showing 3 changed files with 1 addition and 7 deletions.
1 change: 0 additions & 1 deletion nav2_mppi_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,6 @@ set(dependencies_pkgs
geometry_msgs
visualization_msgs
nav_msgs
nav2_msgs
nav2_core
nav2_costmap_2d
nav2_util
Expand Down
2 changes: 1 addition & 1 deletion nav2_mppi_controller/src/controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
5 changes: 0 additions & 5 deletions nav2_mppi_controller/src/critic_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,9 +85,6 @@ void CriticManager::evalTrajectoriesScores(
xt::xtensor<float, 1> CriticManager::evalTrajectory(
CriticData & data) const
{
// log the critic_scores shape
RCLCPP_INFO(logger_, "(BEFORE FOR)");

xt::xtensor<float, 1> critic_scores = xt::zeros<float>({critics_.size()});

for (size_t q = 0; q < critics_.size(); q++) {
Expand All @@ -99,8 +96,6 @@ xt::xtensor<float, 1> 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;
}
Expand Down

0 comments on commit 1f8c9b0

Please sign in to comment.