From 9161d6b87bdb6533111a8e8761b13c98931da8ac Mon Sep 17 00:00:00 2001 From: "Felix Exner (fexner)" Date: Fri, 22 Sep 2023 14:41:29 +0200 Subject: [PATCH] Make depreaction warning for keepalive_counter a warning instead of error (#182) --- src/ur/ur_driver.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/src/ur/ur_driver.cpp b/src/ur/ur_driver.cpp index 60715ccc..9292681b 100644 --- a/src/ur/ur_driver.cpp +++ b/src/ur/ur_driver.cpp @@ -585,11 +585,11 @@ std::vector UrDriver::getRTDEOutputRecipe() void UrDriver::setKeepaliveCount(const uint32_t count) { - URCL_LOG_ERROR("DEPRECATION NOTICE: Setting the keepalive count has been deprecated. Instead use the " - "RobotReceiveTimeout, to set the timeout directly in the write commands. Please change your code to " - "set the " - "read timeout in the write commands directly. This keepalive count will overwrite the timeout passed " - "to the write functions."); + URCL_LOG_WARN("DEPRECATION NOTICE: Setting the keepalive count has been deprecated. Instead use the " + "RobotReceiveTimeout, to set the timeout directly in the write commands. Please change your code to " + "set the " + "read timeout in the write commands directly. This keepalive count will overwrite the timeout passed " + "to the write functions."); reverse_interface_->setKeepaliveCount(count); }