Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
12 changes: 5 additions & 7 deletions controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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");
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}

Expand Down Expand Up @@ -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;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down