diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp index 9fb6df3f85..ca428033fd 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp @@ -73,15 +73,22 @@ BtActionServer::BtActionServer( if (value.get_type() == rclcpp::PARAMETER_NOT_SET) { std::string error_codes_str; for (const auto & error_code : error_code_names) { - error_codes_str += "\n" + error_code; + error_codes_str += " " + error_code; } RCLCPP_WARN_STREAM( - logger_, "Error_code parameters were not set. Using default values of: " + logger_, "Error_code parameters were not set. Using default values of:" << error_codes_str + "\n" << "Make sure these match your BT and there are not other sources of error codes you" "reported to your application"); rclcpp::Parameter error_code_names_param("error_code_names", error_code_names); node->set_parameter(error_code_names_param); + } else { + error_code_names = value.get>(); + std::string error_codes_str; + for (const auto & error_code : error_code_names) { + error_codes_str += " " + error_code; + } + RCLCPP_INFO_STREAM(logger_, "Error_code parameters were set to:" << error_codes_str); } } } @@ -286,7 +293,7 @@ void BtActionServer::populateErrorCode( highest_priority_error_code = current_error_code; } } catch (...) { - RCLCPP_ERROR( + RCLCPP_DEBUG( logger_, "Failed to get error code: %s from blackboard", error_code.c_str());