@@ -230,8 +230,8 @@ controller_interface::CallbackReturn GripperActionController::on_configure(
230
230
231
231
// Action status checking update rate
232
232
action_monitor_period_ = rclcpp::Duration::from_seconds (1.0 / params_.action_monitor_rate );
233
- RCLCPP_INFO_STREAM (
234
- logger, " Action status changes will be monitored at " << params_.action_monitor_rate << " Hz. " );
233
+ RCLCPP_INFO (
234
+ logger, " Action status changes will be monitored at %f Hz. " , params_.action_monitor_rate );
235
235
236
236
// Controlled joint
237
237
if (params_.joint .empty ())
@@ -253,17 +253,16 @@ controller_interface::CallbackReturn GripperActionController::on_activate(
253
253
{ return command_interface.get_interface_name () == hardware_interface::HW_IF_POSITION; });
254
254
if (command_interface_it == command_interfaces_.end ())
255
255
{
256
- RCLCPP_ERROR_STREAM (
257
- get_node ()->get_logger (),
258
- " Expected 1 " << hardware_interface::HW_IF_POSITION << " command interface " );
256
+ RCLCPP_ERROR (
257
+ get_node ()->get_logger (), " Expected 1 %s command interface " ,
258
+ hardware_interface::HW_IF_POSITION);
259
259
return controller_interface::CallbackReturn::ERROR;
260
260
}
261
261
if (command_interface_it->get_prefix_name () != params_.joint )
262
262
{
263
- RCLCPP_ERROR_STREAM (
264
- get_node ()->get_logger (), " Command interface is different than joint name `"
265
- << command_interface_it->get_prefix_name () << " ` != `"
266
- << params_.joint << " `" );
263
+ RCLCPP_ERROR (
264
+ get_node ()->get_logger (), " Command interface is different than joint name `%s` != `%s`" ,
265
+ command_interface_it->get_prefix_name ().c_str (), params_.joint .c_str ());
267
266
return controller_interface::CallbackReturn::ERROR;
268
267
}
269
268
const auto position_state_interface_it = std::find_if (
@@ -277,10 +276,10 @@ controller_interface::CallbackReturn GripperActionController::on_activate(
277
276
}
278
277
if (position_state_interface_it->get_prefix_name () != params_.joint )
279
278
{
280
- RCLCPP_ERROR_STREAM (
281
- get_node ()->get_logger (), " Position state interface is different than joint name ` "
282
- << position_state_interface_it-> get_prefix_name () << " ` != `"
283
- << params_.joint << " ` " );
279
+ RCLCPP_ERROR (
280
+ get_node ()->get_logger (),
281
+ " Position state interface is different than joint name `%s` != `%s` " ,
282
+ position_state_interface_it-> get_prefix_name (). c_str (), params_.joint . c_str () );
284
283
return controller_interface::CallbackReturn::ERROR;
285
284
}
286
285
const auto velocity_state_interface_it = std::find_if (
@@ -294,10 +293,10 @@ controller_interface::CallbackReturn GripperActionController::on_activate(
294
293
}
295
294
if (velocity_state_interface_it->get_prefix_name () != params_.joint )
296
295
{
297
- RCLCPP_ERROR_STREAM (
298
- get_node ()->get_logger (), " Velocity command interface is different than joint name ` "
299
- << velocity_state_interface_it-> get_prefix_name () << " ` != `"
300
- << params_.joint << " ` " );
296
+ RCLCPP_ERROR (
297
+ get_node ()->get_logger (),
298
+ " Velocity command interface is different than joint name `%s` != `%s` " ,
299
+ velocity_state_interface_it-> get_prefix_name (). c_str (), params_.joint . c_str () );
301
300
return controller_interface::CallbackReturn::ERROR;
302
301
}
303
302
0 commit comments