diff --git a/nav2_motion_primitives/src/back_up.cpp b/nav2_motion_primitives/src/back_up.cpp index 18dde9809923b71e510d10a61f4dbf0428245bc0..a49838b96e739a468bbb4729af6e76aebac77009 100644 --- a/nav2_motion_primitives/src/back_up.cpp +++ b/nav2_motion_primitives/src/back_up.cpp @@ -82,7 +82,7 @@ Status BackUp::onCycleUpdate() if (!collision_checker_->isCollisionFree(pose2d)) { stopRobot(); - RCLCPP_INFO(node_->get_logger(), "Collision Ahead - Exiting BackUp"); + RCLCPP_WARN(node_->get_logger(), "Collision Ahead - Exiting BackUp"); return Status::SUCCEEDED; } diff --git a/nav2_motion_primitives/src/spin.cpp b/nav2_motion_primitives/src/spin.cpp index 31fd4fb1358183f69ff3204ebd6a72b9677f0935..b6756ee816256517c807835c9b119b5dd10c14ea 100644 --- a/nav2_motion_primitives/src/spin.cpp +++ b/nav2_motion_primitives/src/spin.cpp @@ -102,7 +102,7 @@ Status Spin::timedSpin() if (!collision_checker_->isCollisionFree(pose2d)) { stopRobot(); - RCLCPP_INFO(node_->get_logger(), "Collision Ahead -Exiting Spin "); + RCLCPP_WARN(node_->get_logger(), "Collision Ahead -Exiting Spin "); return Status::SUCCEEDED; }