diff --git a/controller_manager/src/controller_manager.cpp b/controller_manager/src/controller_manager.cpp index 3ebc1a9a14..eb79eefc19 100644 --- a/controller_manager/src/controller_manager.cpp +++ b/controller_manager/src/controller_manager.cpp @@ -443,17 +443,15 @@ controller_interface::return_type ControllerManager::switch_controller( auto handle_conflict = [&](const std::string & msg) { if (strictness == controller_manager_msgs::srv::SwitchController::Request::STRICT) { - RCLCPP_ERROR_STREAM( - get_logger(), - msg); + RCLCPP_ERROR(get_logger(), "%s", msg.c_str()); stop_request_.clear(); start_request_.clear(); return controller_interface::return_type::ERROR; } - RCLCPP_DEBUG_STREAM( + RCLCPP_DEBUG( get_logger(), - "Could not stop controller '" << controller.info.name << - "' since it is not running"); + "Could not stop controller '%s' since it is not running", + controller.info.name.c_str()); return controller_interface::return_type::OK; }; if (!is_running && in_stop_list) { // check for double stop @@ -745,7 +743,7 @@ void ControllerManager::list_controller_types_srv_cb( for (const auto & cur_type : cur_types) { response->types.push_back(cur_type); response->base_classes.push_back(kControllerInterface); - RCLCPP_DEBUG_STREAM(get_logger(), cur_type); + RCLCPP_DEBUG(get_logger(), "%s", cur_type.c_str()); } RCLCPP_DEBUG(get_logger(), "list types service finished"); diff --git a/joint_limits_interface/include/joint_limits_interface/joint_limits_rosparam.hpp b/joint_limits_interface/include/joint_limits_interface/joint_limits_rosparam.hpp index b83114fdd5..473b72e514 100644 --- a/joint_limits_interface/include/joint_limits_interface/joint_limits_rosparam.hpp +++ b/joint_limits_interface/include/joint_limits_interface/joint_limits_rosparam.hpp @@ -84,14 +84,17 @@ inline bool getJointLimits( !node->has_parameter(param_base_name + ".soft_lower_limit") && !node->has_parameter(param_base_name + ".soft_upper_limit")) { - RCLCPP_ERROR_STREAM( - node->get_logger(), "No joint limits specification found for joint '" << joint_name << - "' in the parameter server (node: " << std::string( - node->get_name()) + " param name: " + param_base_name << ")."); + RCLCPP_ERROR( + node->get_logger(), + "No joint limits specification found for joint '%s' in the parameter server " + "(node: %s param name: %s).", + joint_name.c_str(), + node->get_name(), + param_base_name.c_str()); return false; } } catch (const std::exception & ex) { - RCLCPP_ERROR_STREAM(node->get_logger(), ex.what()); + RCLCPP_ERROR(node->get_logger(), "%s", ex.what()); return false; } @@ -200,14 +203,17 @@ inline bool getSoftJointLimits( !node->has_parameter(param_base_name + ".soft_lower_limit") && !node->has_parameter(param_base_name + ".soft_upper_limit")) { - RCLCPP_DEBUG_STREAM( - node->get_logger(), "No soft joint limits specification found for joint '" << joint_name << - "' in the parameter server (node: " << std::string( - node->get_name()) + " param name: " + param_base_name << ")."); + RCLCPP_DEBUG( + node->get_logger(), + "No soft joint limits specification found for joint '%s' in the parameter server " + "(node: %s param name: %s).", + joint_name.c_str(), + node->get_name(), + param_base_name.c_str()); return false; } } catch (const std::exception & ex) { - RCLCPP_ERROR_STREAM(node->get_logger(), ex.what()); + RCLCPP_ERROR(node->get_logger(), "%s", ex.what()); return false; } diff --git a/joint_limits_interface/test/joint_limits_interface_test.cpp b/joint_limits_interface/test/joint_limits_interface_test.cpp index 23226773a6..7d14410c9d 100644 --- a/joint_limits_interface/test/joint_limits_interface_test.cpp +++ b/joint_limits_interface/test/joint_limits_interface_test.cpp @@ -538,7 +538,7 @@ class JointLimitsInterfaceTest : public JointLimitsTest, public ::testing::Test // try { // iface.getHandle("unknown_name"); // } catch (const JointLimitsInterfaceException & e) { -// ROS_ERROR_STREAM(e.what()); +// ROS_ERROR("%s", e.what()); // } // // // Enforce limits of all managed joints