From 023cdd5ba1849f4e0987ad51d32dfd6b85836c06 Mon Sep 17 00:00:00 2001 From: Mohammad Haghighipanah <mohammad.haghighipanah@intel.com> Date: Tue, 18 Jun 2019 15:23:15 -0700 Subject: [PATCH] Changed unnecessary info messeges to debug --- nav2_costmap_2d/plugins/static_layer.cpp | 4 ++-- nav2_dwb_controller/dwb_controller/src/dwb_controller.cpp | 2 +- nav2_navfn_planner/src/navfn_planner.cpp | 4 ++-- nav2_world_model/src/world_model.cpp | 2 +- 4 files changed, 6 insertions(+), 6 deletions(-) diff --git a/nav2_costmap_2d/plugins/static_layer.cpp b/nav2_costmap_2d/plugins/static_layer.cpp index 63218c0b..afa17433 100644 --- a/nav2_costmap_2d/plugins/static_layer.cpp +++ b/nav2_costmap_2d/plugins/static_layer.cpp @@ -75,7 +75,7 @@ StaticLayer::onInitialize() getMap(); if (!first_map_only_) { - RCLCPP_INFO(node_->get_logger(), "Subscribing to the map topic (%s)", map_topic_.c_str()); + RCLCPP_DEBUG(node_->get_logger(), "Subscribing to the map topic (%s)", map_topic_.c_str()); map_sub_ = node_->create_subscription<nav_msgs::msg::OccupancyGrid>(map_topic_, rclcpp::SystemDefaultsQoS(), std::bind(&StaticLayer::incomingMap, this, std::placeholders::_1)); @@ -152,7 +152,7 @@ StaticLayer::getMap() void StaticLayer::processMap(const nav_msgs::msg::OccupancyGrid & new_map) { - RCLCPP_INFO(node_->get_logger(), "StaticLayer: Process map"); + RCLCPP_DEBUG(node_->get_logger(), "StaticLayer: Process map"); unsigned int size_x = new_map.info.width; unsigned int size_y = new_map.info.height; diff --git a/nav2_dwb_controller/dwb_controller/src/dwb_controller.cpp b/nav2_dwb_controller/dwb_controller/src/dwb_controller.cpp index 1edf9cb7..dc6ac0af 100644 --- a/nav2_dwb_controller/dwb_controller/src/dwb_controller.cpp +++ b/nav2_dwb_controller/dwb_controller/src/dwb_controller.cpp @@ -171,7 +171,7 @@ DwbController::followPath(const std::shared_ptr<GoalHandle> goal_handle) // Check if there is an update to the path to follow if (action_server_->preempt_requested()) { - RCLCPP_INFO(get_logger(), "Received a new goal, pre-empting the old one"); + RCLCPP_DEBUG(get_logger(), "Received a new goal, pre-empting the old one"); current_goal_handle = action_server_->get_updated_goal_handle(); goal = current_goal_handle->get_goal(); diff --git a/nav2_navfn_planner/src/navfn_planner.cpp b/nav2_navfn_planner/src/navfn_planner.cpp index 4b33070d..0ba850d6 100644 --- a/nav2_navfn_planner/src/navfn_planner.cpp +++ b/nav2_navfn_planner/src/navfn_planner.cpp @@ -183,7 +183,7 @@ NavfnPlanner::computePathToPose(const std::shared_ptr<GoalHandle> goal_handle) return; } - RCLCPP_INFO(get_logger(), "Attempting to a find path from (%.2f, %.2f) to " + RCLCPP_DEBUG(get_logger(), "Attempting to a find path from (%.2f, %.2f) to " "(%.2f, %.2f).", start->pose.pose.position.x, start->pose.pose.position.y, goal->pose.pose.position.x, goal->pose.pose.position.y); @@ -213,7 +213,7 @@ NavfnPlanner::computePathToPose(const std::shared_ptr<GoalHandle> goal_handle) // TODO(orduno): Enable potential visualization - RCLCPP_INFO(get_logger(), + RCLCPP_DEBUG(get_logger(), "Successfully computed a path to (%.2f, %.2f) with tolerance %.2f", goal->pose.pose.position.x, goal->pose.pose.position.y, tolerance_); goal_handle->succeed(result); diff --git a/nav2_world_model/src/world_model.cpp b/nav2_world_model/src/world_model.cpp index 1b6ae3ea..37a10459 100644 --- a/nav2_world_model/src/world_model.cpp +++ b/nav2_world_model/src/world_model.cpp @@ -105,7 +105,7 @@ WorldModel::costmap_service_callback( const std::shared_ptr<nav2_msgs::srv::GetCostmap::Request>/*request*/, const std::shared_ptr<nav2_msgs::srv::GetCostmap::Response> response) { - RCLCPP_INFO(get_logger(), "Received costmap service request"); + RCLCPP_DEBUG(get_logger(), "Received costmap service request"); // TODO(bpwilcox): Grab correct orientation information tf2::Quaternion quaternion; -- GitLab