Skip to content

Commit 64c00ea

Browse files
Fix -Wunused-result warnings in JTC (#1831)
1 parent 9a5cf64 commit 64c00ea

File tree

2 files changed

+14
-6
lines changed

2 files changed

+14
-6
lines changed

joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp

Lines changed: 9 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -319,7 +319,15 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
319319
{
320320
for (size_t index = 0; index < num_cmd_joints_; ++index)
321321
{
322-
joint_interface[index].get().set_value(trajectory_point_interface[map_cmd_to_joints_[index]]);
322+
if (!joint_interface[index].get().set_value(
323+
trajectory_point_interface[map_cmd_to_joints_[index]]))
324+
{
325+
RCLCPP_ERROR(
326+
get_node()->get_logger(),
327+
"Failed to set value for joint '%s' in command interface '%s'. ",
328+
command_joint_names_[index].c_str(), joint_interface[index].get().get_name().c_str());
329+
return;
330+
}
323331
}
324332
}
325333
};

joint_trajectory_controller/test/test_trajectory_controller_utils.hpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -387,15 +387,15 @@ class TrajectoryControllerTest : public ::testing::Test
387387
joint_names_[i], hardware_interface::HW_IF_ACCELERATION,
388388
separate_cmd_and_state_values ? &joint_state_acc_[i] : &joint_acc_[i]));
389389

390-
// Add to export lists and set initial values
390+
// Add to export lists and set initial values (explicitly discarding return value)
391391
cmd_interfaces.emplace_back(pos_cmd_interfaces_.back());
392-
cmd_interfaces.back().set_value(initial_pos_joints[i]);
392+
(void)cmd_interfaces.back().set_value(initial_pos_joints[i]);
393393
cmd_interfaces.emplace_back(vel_cmd_interfaces_.back());
394-
cmd_interfaces.back().set_value(initial_vel_joints[i]);
394+
(void)cmd_interfaces.back().set_value(initial_vel_joints[i]);
395395
cmd_interfaces.emplace_back(acc_cmd_interfaces_.back());
396-
cmd_interfaces.back().set_value(initial_acc_joints[i]);
396+
(void)cmd_interfaces.back().set_value(initial_acc_joints[i]);
397397
cmd_interfaces.emplace_back(eff_cmd_interfaces_.back());
398-
cmd_interfaces.back().set_value(initial_eff_joints[i]);
398+
(void)cmd_interfaces.back().set_value(initial_eff_joints[i]);
399399
if (separate_cmd_and_state_values)
400400
{
401401
joint_state_pos_[i] = INITIAL_POS_JOINTS[i];

0 commit comments

Comments
 (0)