diff --git a/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp b/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp index ed364f0987f4f..5d1c0c68d8208 100644 --- a/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp +++ b/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp @@ -400,7 +400,7 @@ PlannerPlugin::LaneletRoute DefaultPlanner::plan(const RoutePoints & points) log_ss << "x: " << point.position.x << " " << "y: " << point.position.y << std::endl; } - RCLCPP_INFO_STREAM( + RCLCPP_DEBUG_STREAM( logger, "start planning route with check points: " << std::endl << log_ss.str()); diff --git a/planning/mission_planner/src/mission_planner/mission_planner.cpp b/planning/mission_planner/src/mission_planner/mission_planner.cpp index a1536a1bebfbf..9ee874928d7d1 100644 --- a/planning/mission_planner/src/mission_planner/mission_planner.cpp +++ b/planning/mission_planner/src/mission_planner/mission_planner.cpp @@ -144,7 +144,7 @@ void MissionPlanner::checkInitialization() } // All data is ready. Now API is available. - RCLCPP_INFO(get_logger(), "Route API is ready."); + RCLCPP_DEBUG(get_logger(), "Route API is ready."); change_state(RouteState::Message::UNSET); data_check_timer_->cancel(); // stop timer callback }