Skip to content

Commit eca84fa

Browse files
authored
Replace RCLCPP_*_STREAM macros with RCLCPP_* (#1600)
1 parent ac35696 commit eca84fa

File tree

5 files changed

+49
-48
lines changed

5 files changed

+49
-48
lines changed

admittance_controller/src/admittance_controller.cpp

+5-4
Original file line numberDiff line numberDiff line change
@@ -299,10 +299,11 @@ controller_interface::CallbackReturn AdmittanceController::on_configure(
299299
msg.header.frame_id != admittance_->parameters_.ft_sensor.frame.id &&
300300
!msg.header.frame_id.empty())
301301
{
302-
RCLCPP_ERROR_STREAM(
303-
get_node()->get_logger(), "Ignoring wrench reference as it is on the wrong frame: "
304-
<< msg.header.frame_id << ". Expected reference frame: "
305-
<< admittance_->parameters_.ft_sensor.frame.id);
302+
RCLCPP_ERROR(
303+
get_node()->get_logger(),
304+
"Ignoring wrench reference as it is on the wrong frame: %s. Expected reference frame: "
305+
"%s",
306+
msg.header.frame_id.c_str(), admittance_->parameters_.ft_sensor.frame.id.c_str());
306307
return;
307308
}
308309
input_wrench_command_.writeFromNonRT(msg);

gripper_controllers/include/gripper_controllers/gripper_action_controller_impl.hpp

+14-16
Original file line numberDiff line numberDiff line change
@@ -210,8 +210,8 @@ controller_interface::CallbackReturn GripperActionController<HardwareInterface>:
210210

211211
// Action status checking update rate
212212
action_monitor_period_ = rclcpp::Duration::from_seconds(1.0 / params_.action_monitor_rate);
213-
RCLCPP_INFO_STREAM(
214-
logger, "Action status changes will be monitored at " << params_.action_monitor_rate << "Hz.");
213+
RCLCPP_INFO(
214+
logger, "Action status changes will be monitored at %f Hz.", params_.action_monitor_rate);
215215

216216
// Controlled joint
217217
if (params_.joint.empty())
@@ -232,16 +232,14 @@ controller_interface::CallbackReturn GripperActionController<HardwareInterface>:
232232
{ return command_interface.get_interface_name() == HardwareInterface; });
233233
if (command_interface_it == command_interfaces_.end())
234234
{
235-
RCLCPP_ERROR_STREAM(
236-
get_node()->get_logger(), "Expected 1 " << HardwareInterface << " command interface");
235+
RCLCPP_ERROR(get_node()->get_logger(), "Expected 1 %s command interface", HardwareInterface);
237236
return controller_interface::CallbackReturn::ERROR;
238237
}
239238
if (command_interface_it->get_prefix_name() != params_.joint)
240239
{
241-
RCLCPP_ERROR_STREAM(
242-
get_node()->get_logger(), "Command interface is different than joint name `"
243-
<< command_interface_it->get_prefix_name() << "` != `"
244-
<< params_.joint << "`");
240+
RCLCPP_ERROR(
241+
get_node()->get_logger(), "Command interface is different than joint name `%s` != `%s`",
242+
command_interface_it->get_prefix_name().c_str(), params_.joint.c_str());
245243
return controller_interface::CallbackReturn::ERROR;
246244
}
247245
const auto position_state_interface_it = std::find_if(
@@ -255,10 +253,10 @@ controller_interface::CallbackReturn GripperActionController<HardwareInterface>:
255253
}
256254
if (position_state_interface_it->get_prefix_name() != params_.joint)
257255
{
258-
RCLCPP_ERROR_STREAM(
259-
get_node()->get_logger(), "Position state interface is different than joint name `"
260-
<< position_state_interface_it->get_prefix_name() << "` != `"
261-
<< params_.joint << "`");
256+
RCLCPP_ERROR(
257+
get_node()->get_logger(),
258+
"Position state interface is different than joint name `%s` != `%s`",
259+
position_state_interface_it->get_prefix_name().c_str(), params_.joint.c_str());
262260
return controller_interface::CallbackReturn::ERROR;
263261
}
264262
const auto velocity_state_interface_it = std::find_if(
@@ -272,10 +270,10 @@ controller_interface::CallbackReturn GripperActionController<HardwareInterface>:
272270
}
273271
if (velocity_state_interface_it->get_prefix_name() != params_.joint)
274272
{
275-
RCLCPP_ERROR_STREAM(
276-
get_node()->get_logger(), "Velocity command interface is different than joint name `"
277-
<< velocity_state_interface_it->get_prefix_name() << "` != `"
278-
<< params_.joint << "`");
273+
RCLCPP_ERROR(
274+
get_node()->get_logger(),
275+
"Velocity command interface is different than joint name `%s` != `%s`",
276+
velocity_state_interface_it->get_prefix_name().c_str(), params_.joint.c_str());
279277
return controller_interface::CallbackReturn::ERROR;
280278
}
281279

joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -53,7 +53,7 @@ const std::unordered_map<InterpolationMethod, std::string> InterpolationMethodMa
5353
// Default
5454
else
5555
{
56-
RCLCPP_INFO_STREAM(
56+
RCLCPP_INFO(
5757
LOGGER,
5858
"No interpolation method parameter was given. Using the default, VARIABLE_DEGREE_SPLINE.");
5959
return InterpolationMethod::VARIABLE_DEGREE_SPLINE;

joint_trajectory_controller/include/joint_trajectory_controller/tolerances.hpp

+13-10
Original file line numberDiff line numberDiff line change
@@ -175,10 +175,9 @@ SegmentTolerances get_segment_tolerances(
175175
}
176176
catch (const std::runtime_error & e)
177177
{
178-
RCLCPP_ERROR_STREAM(
179-
logger, "Specified illegal goal_time_tolerance: "
180-
<< rclcpp::Duration(goal.goal_time_tolerance).seconds()
181-
<< ". Using default tolerances");
178+
RCLCPP_ERROR(
179+
logger, "Specified illegal goal_time_tolerance: %f. Using default tolerances",
180+
rclcpp::Duration(goal.goal_time_tolerance).seconds());
182181
return default_tolerances;
183182
}
184183
RCLCPP_DEBUG(logger, "%s %f", "goal_time", active_tolerances.goal_time_tolerance);
@@ -215,9 +214,11 @@ SegmentTolerances get_segment_tolerances(
215214
}
216215
catch (const std::runtime_error & e)
217216
{
218-
RCLCPP_ERROR_STREAM(
219-
logger, "joint '" << joint << "' specified in goal.path_tolerance has a invalid "
220-
<< interface << " tolerance. Using default tolerances.");
217+
RCLCPP_ERROR(
218+
logger,
219+
"joint '%s' specified in goal.path_tolerance has a invalid %s tolerance. Using default "
220+
"tolerances.",
221+
joint.c_str(), interface.c_str());
221222
return default_tolerances;
222223
}
223224

@@ -262,9 +263,11 @@ SegmentTolerances get_segment_tolerances(
262263
}
263264
catch (const std::runtime_error & e)
264265
{
265-
RCLCPP_ERROR_STREAM(
266-
logger, "joint '" << joint << "' specified in goal.goal_tolerance has a invalid "
267-
<< interface << " tolerance. Using default tolerances.");
266+
RCLCPP_ERROR(
267+
logger,
268+
"joint '%s' specified in goal.goal_tolerance has a invalid %s tolerance. Using default "
269+
"tolerances.",
270+
joint.c_str(), interface.c_str());
268271
return default_tolerances;
269272
}
270273

parallel_gripper_controller/include/parallel_gripper_controller/parallel_gripper_action_controller_impl.hpp

+16-17
Original file line numberDiff line numberDiff line change
@@ -230,8 +230,8 @@ controller_interface::CallbackReturn GripperActionController::on_configure(
230230

231231
// Action status checking update rate
232232
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);
235235

236236
// Controlled joint
237237
if (params_.joint.empty())
@@ -253,17 +253,16 @@ controller_interface::CallbackReturn GripperActionController::on_activate(
253253
{ return command_interface.get_interface_name() == hardware_interface::HW_IF_POSITION; });
254254
if (command_interface_it == command_interfaces_.end())
255255
{
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);
259259
return controller_interface::CallbackReturn::ERROR;
260260
}
261261
if (command_interface_it->get_prefix_name() != params_.joint)
262262
{
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());
267266
return controller_interface::CallbackReturn::ERROR;
268267
}
269268
const auto position_state_interface_it = std::find_if(
@@ -277,10 +276,10 @@ controller_interface::CallbackReturn GripperActionController::on_activate(
277276
}
278277
if (position_state_interface_it->get_prefix_name() != params_.joint)
279278
{
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());
284283
return controller_interface::CallbackReturn::ERROR;
285284
}
286285
const auto velocity_state_interface_it = std::find_if(
@@ -294,10 +293,10 @@ controller_interface::CallbackReturn GripperActionController::on_activate(
294293
}
295294
if (velocity_state_interface_it->get_prefix_name() != params_.joint)
296295
{
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());
301300
return controller_interface::CallbackReturn::ERROR;
302301
}
303302

0 commit comments

Comments
 (0)