Skip to content

Commit 6a4e7a6

Browse files
[JTC] Reject messages with effort fields (ros-controls#699) (ros-controls#719) (ros-controls#738)
1 parent 862928c commit 6a4e7a6

File tree

2 files changed

+13
-16
lines changed

2 files changed

+13
-16
lines changed

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 12 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -292,14 +292,7 @@ controller_interface::return_type JointTrajectoryController::update(
292292
}
293293
if (has_effort_command_interface_)
294294
{
295-
if (use_closed_loop_pid_adapter_)
296-
{
297-
assign_interface_from_point(joint_command_interface_[3], tmp_command_);
298-
}
299-
else
300-
{
301-
assign_interface_from_point(joint_command_interface_[3], state_desired_.effort);
302-
}
295+
assign_interface_from_point(joint_command_interface_[3], tmp_command_);
303296
}
304297

305298
// store the previous command. Used in open-loop control mode
@@ -1364,8 +1357,9 @@ bool JointTrajectoryController::validate_trajectory_point_field(
13641357
if (joint_names_size != vector_field.size())
13651358
{
13661359
RCLCPP_ERROR(
1367-
get_node()->get_logger(), "Mismatch between joint_names (%zu) and %s (%zu) at point #%zu.",
1368-
joint_names_size, string_for_vector_field.c_str(), vector_field.size(), i);
1360+
get_node()->get_logger(),
1361+
"Mismatch between joint_names size (%zu) and %s (%zu) at point #%zu.", joint_names_size,
1362+
string_for_vector_field.c_str(), vector_field.size(), i);
13691363
return false;
13701364
}
13711365
return true;
@@ -1481,11 +1475,17 @@ bool JointTrajectoryController::validate_trajectory_msg(
14811475
!validate_trajectory_point_field(joint_count, points[i].positions, "positions", i, false) ||
14821476
!validate_trajectory_point_field(joint_count, points[i].velocities, "velocities", i, true) ||
14831477
!validate_trajectory_point_field(
1484-
joint_count, points[i].accelerations, "accelerations", i, true) ||
1485-
!validate_trajectory_point_field(joint_count, points[i].effort, "effort", i, true))
1478+
joint_count, points[i].accelerations, "accelerations", i, true))
14861479
{
14871480
return false;
14881481
}
1482+
// reject effort entries
1483+
if (!points[i].effort.empty())
1484+
{
1485+
RCLCPP_ERROR(
1486+
get_node()->get_logger(), "Trajectories with effort fields are currently not supported.");
1487+
return false;
1488+
}
14891489
}
14901490
return true;
14911491
}

joint_trajectory_controller/test/test_trajectory_controller.cpp

Lines changed: 1 addition & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1110,13 +1110,10 @@ TEST_P(TrajectoryControllerTestParameterized, invalid_message)
11101110
traj_msg.points[0].accelerations = {1.0, 2.0};
11111111
EXPECT_FALSE(traj_controller_->validate_trajectory_msg(traj_msg));
11121112

1113-
// Effort is not supported in trajectory message
1114-
#if 0
1115-
// TODO(christophfroehlich) activate with #730
1113+
// Effort is not supported in trajectory message
11161114
traj_msg = good_traj_msg;
11171115
traj_msg.points[0].effort = {1.0, 2.0, 3.0};
11181116
EXPECT_FALSE(traj_controller_->validate_trajectory_msg(traj_msg));
1119-
#endif
11201117

11211118
// Non-strictly increasing waypoint times
11221119
traj_msg = good_traj_msg;

0 commit comments

Comments
 (0)